Cartesian Task API
-
class XBot::Cartesian::CartesianTask : public virtual XBot::Cartesian::TaskDescription
Abstract interface of a cartesian task.
Subclassed by XBot::Cartesian::CartesianRt, XBot::Cartesian::CartesianTaskImpl, XBot::Cartesian::ClientApi::CartesianRos, XBot::Cartesian::ComTask, XBot::Cartesian::GazeTask, XBot::Cartesian::InteractionTask
Public Functions
-
virtual const std::string &getBaseLink() const = 0
getter for the task base link
-
virtual bool setBaseLink(const std::string &new_base_link) = 0
setBaseLink changes the task base link with the provided one
- Parameters
new_base_link – must belong to the model kinematic tree
- Returns
true if the new base link is valid and the operation was successful
-
virtual const std::string &getDistalLink() const = 0
getter for the task distal link
-
virtual ControlType getControlMode() const = 0
getter for the task current control mode (i.e. Position, or Velocity)
-
virtual bool setControlMode(const ControlType &value) = 0
setControlMode changes the current control mode
- Returns
true if the operation was successful
-
virtual State getTaskState() const = 0
getter for the current task state, which indicates if the task is currently performing a reaching motion, or if it is available for online control
-
virtual bool isSubtaskLocal() const = 0
isSubtaskLocal returns true if subtasks extracted from this task should be in local (distal link) coordinates, and false otherwise (base link coordinates)
-
virtual bool getCurrentPose(Eigen::Affine3d &base_T_ee) const = 0
getCurrentPose returns the current pose value of the task, i.e. the pose of distal link relative to base link at the current solution (i.e. the model state)
- Parameters
base_T_ee – is filled in by the function
- Returns
true on success
-
virtual bool getPoseReference(Eigen::Affine3d &base_T_ref, Eigen::Vector6d *base_vel_ref = nullptr, Eigen::Vector6d *base_acc_ref = nullptr) const = 0
getPoseReference returns the current desired value for the task pose, and optionally velocity and acceleration
- Parameters
base_T_ref – reference to desired pose
base_vel_ref – pointer to desired velocity
base_acc_ref – pointer to desired acceleration
- Returns
true on success
-
virtual bool getPoseReferenceRaw(Eigen::Affine3d &base_T_ref, Eigen::Vector6d *base_vel_ref = nullptr, Eigen::Vector6d *base_acc_ref = nullptr) const = 0
getPoseReferenceRaw returns the current desired value for the task pose, and optionally velocity and acceleration. The returned value is BEFORE any filtering or online trajectory generation being performed by the task. The references which are actually fed to the controller are instead given by getReferencePose.
- Parameters
base_T_ref – reference to desired pose
base_vel_ref – pointer to desired velocity
base_acc_ref – pointer to desired acceleration
- Returns
true on success
-
virtual bool setPoseReference(const Eigen::Affine3d &base_T_ref) = 0
setPoseReference sets a new pose reference for the controller. If enableOnlineTrajectoryGeneration() was called, the provided reference is saturated according to the active velocity and acceleration limits.
- Parameters
base_T_ref – the new reference
- Returns
true on success
-
virtual bool setPoseReferenceRaw(const Eigen::Affine3d &base_T_ref) = 0
setPoseReferenceRaw does the same as setPoseReference, but bypasses any trajectory generation. It is therefore less safe to use.
-
virtual bool setVelocityReference(const Eigen::Vector6d &base_vel_ref) = 0
setVelocityReference sets a new desired velocity for the task.
- Returns
-
virtual bool getPoseTarget(Eigen::Affine3d &base_T_ref) const = 0
getPoseTarget returns the current of the reaching motion being performed by the task, if the task state is Reaching.
- Returns
true if the task state is Reaching, false otherwise
-
virtual bool setPoseTarget(const Eigen::Affine3d &base_T_ref, double time) = 0
setPoseTarget commands a reaching motion to the given target
- Parameters
base_T_ref – the pose to be reached
time – the time (in seconds) to reach the task
- Returns
true on success, i.e. the task state was ‘Online`
-
virtual bool setWayPoints(const Trajectory::WayPointVector &way_points) = 0
setWayPoints commands a reaching motion through the specified list of waypoints
- Parameters
way_points – a std::vector of WayPoints, each of which specifies a frame, and a time relative to the trajectory start
- Returns
true on success, i.e. the task state was ‘Online’
-
virtual int getCurrentSegmentId() const = 0
getCurrentSegmentId returns the trajectory segment id currently being performed, or -1 if the task state is ‘Online’
-
virtual void abort() = 0
abort interrupts any reaching motion
-
virtual void getVelocityLimits(double &max_vel_lin, double &max_vel_ang) const = 0
getVelocityLimits return the currently active velocity limits for linear and angular motions
-
virtual void getAccelerationLimits(double &max_acc_lin, double &max_acc_ang) const = 0
getAccelerationLimits return the currently active acceleration limits for linear and angular motions
-
virtual void setVelocityLimits(double max_vel_lin, double max_vel_ang) = 0
setVelocityLimits sets new velocity limits for linear and angular motions
-
virtual void setAccelerationLimits(double max_acc_lin, double max_acc_ang) = 0
setAccelerationLimits sets new acceleration limits for linear and angular motions
-
virtual const std::string &getBaseLink() const = 0