RobotTemplate¶
- class RobotTemplate(self)¶
Bases:
Robot
Class that defines a robot just to show which function you must implement.
Default constructor.
Methods
Default constructor.
Overloaded function.
Get the robot Jacobian expressed in the end-effector frame.
Return constant transformation between end-effector and tool frame.
Get the robot Jacobian expressed in the robot reference frame.
Set constant transformation between end-effector and tool frame.
Inherited Methods
STATE_VELOCITY_CONTROL
MIXT_FRAME
Return robot degrees of freedom number.
Robot control frames.
REFERENCE_FRAME
STATE_POSITION_CONTROL
Robot control frames.
STATE_ACCELERATION_CONTROL
CAMERA_FRAME
Get the maximal translation velocity that can be sent to the robot during a velocity control.
Set the maximal rotation velocity that can be sent to the robot during a velocity control.
TOOL_FRAME
JOINT_STATE
STATE_STOP
END_EFFECTOR_FRAME
ARTICULAR_FRAME
Saturate velocities.
Set the maximal translation velocity that can be sent to the robot during a velocity control.
STATE_FORCE_TORQUE_CONTROL
Get the maximal rotation velocity that can be sent to the robot during a velocity control.
Operators
__doc__
Default constructor.
__module__
Attributes
ARTICULAR_FRAME
CAMERA_FRAME
END_EFFECTOR_FRAME
JOINT_STATE
MIXT_FRAME
REFERENCE_FRAME
STATE_ACCELERATION_CONTROL
STATE_FORCE_TORQUE_CONTROL
STATE_POSITION_CONTROL
STATE_STOP
STATE_VELOCITY_CONTROL
TOOL_FRAME
__annotations__
- class ControlFrameType(self, value: int)¶
Bases:
pybind11_object
Robot control frames.
Values:
REFERENCE_FRAME: Corresponds to a fixed reference frame attached to the robot structure.
ARTICULAR_FRAME: Corresponds to the joint state. This value is deprecated. You should rather use vpRobot::JOINT_STATE .
JOINT_STATE: Corresponds to the joint state.
END_EFFECTOR_FRAME: Corresponds to robot end-effector frame.
CAMERA_FRAME: Corresponds to a frame attached to the camera mounted on the robot end-effector.
TOOL_FRAME: Corresponds to a frame attached to the tool (camera, gripper…) mounted on the robot end-effector. This value is equal to vpRobot::CAMERA_FRAME .
MIXT_FRAME: Corresponds to a “virtual” frame where translations are expressed in the reference frame, and rotations in the camera frame.
- class RobotStateType(self, value: int)¶
Bases:
pybind11_object
Robot control frames.
Values:
REFERENCE_FRAME: Corresponds to a fixed reference frame attached to the robot structure.
ARTICULAR_FRAME: Corresponds to the joint state. This value is deprecated. You should rather use vpRobot::JOINT_STATE .
JOINT_STATE: Corresponds to the joint state.
END_EFFECTOR_FRAME: Corresponds to robot end-effector frame.
CAMERA_FRAME: Corresponds to a frame attached to the camera mounted on the robot end-effector.
TOOL_FRAME: Corresponds to a frame attached to the tool (camera, gripper…) mounted on the robot end-effector. This value is equal to vpRobot::CAMERA_FRAME .
MIXT_FRAME: Corresponds to a “virtual” frame where translations are expressed in the reference frame, and rotations in the camera frame.
- __init__(self)¶
Default constructor.
- getDisplacement(self, frame: visp._visp.robot.Robot.ControlFrameType, q: visp._visp.core.ColVector) None ¶
- getMaxRotationVelocity(self) float ¶
Get the maximal rotation velocity that can be sent to the robot during a velocity control.
- Returns:
Maximum rotation velocity expressed in rad/s.
- getMaxTranslationVelocity(self) float ¶
Get the maximal translation velocity that can be sent to the robot during a velocity control.
- Returns:
Maximum translational velocity expressed in m/s.
- getPosition(*args, **kwargs)¶
Overloaded function.
getPosition(self: visp._visp.robot.RobotTemplate, frame: visp._visp.robot.Robot.ControlFrameType, q: visp._visp.core.ColVector) -> None
getPosition(self: visp._visp.robot.Robot, frame: visp._visp.robot.Robot.ControlFrameType) -> visp._visp.core.ColVector
- getRobotState(self) visp._visp.robot.Robot.RobotStateType ¶
- get_eJe(self, eJe_: visp._visp.core.Matrix) None ¶
Get the robot Jacobian expressed in the end-effector frame.
- Parameters:
- eJe_: visp._visp.core.Matrix¶
End-effector frame Jacobian.
- get_eMc(self) visp._visp.core.HomogeneousMatrix ¶
Return constant transformation between end-effector and tool frame. If your tool is a camera, this transformation is obtained by hand-eye calibration.
- get_fJe(self, fJe_: visp._visp.core.Matrix) None ¶
Get the robot Jacobian expressed in the robot reference frame.
- Parameters:
- fJe_: visp._visp.core.Matrix¶
Base (or reference) frame Jacobian.
- static saturateVelocities(v_in: visp._visp.core.ColVector, v_max: visp._visp.core.ColVector, verbose: bool = false) visp._visp.core.ColVector ¶
Saturate velocities.
The code below shows how to use this static method in order to saturate a velocity skew vector.
#include <iostream> #include <visp3/robot/vpRobot.h> #ifdef ENABLE_VISP_NAMESPACE using namespace VISP_NAMESPACE_NAME; #endif int main() { // Set a velocity skew vector vpColVector v(6); v[0] = 0.1; // vx in m/s v[1] = 0.2; // vy v[2] = 0.3; // vz v[3] = vpMath::rad(10); // wx in rad/s v[4] = vpMath::rad(-10); // wy v[5] = vpMath::rad(20); // wz // Set the maximal allowed velocities vpColVector v_max(6); for (int i=0; i<3; i++) v_max[i] = 0.3; // in translation (m/s) for (int i=3; i<6; i++) v_max[i] = vpMath::rad(10); // in rotation (rad/s) // Compute the saturated velocity skew vector vpColVector v_sat = vpRobot::saturateVelocities(v, v_max, true); std::cout << "v : " << v.t() << std::endl; std::cout << "v max: " << v_max.t() << std::endl; std::cout << "v sat: " << v_sat.t() << std::endl; return 0; }
- Parameters:
- v_in: visp._visp.core.ColVector¶
Vector of input velocities to saturate. Translation velocities should be expressed in m/s while rotation velocities in rad/s.
- v_max: visp._visp.core.ColVector¶
Vector of maximal allowed velocities. Maximal translation velocities should be expressed in m/s while maximal rotation velocities in rad/s.
- verbose: bool = false¶
Print a message indicating which axis causes the saturation.
- Returns:
Saturated velocities.
- setMaxRotationVelocity(self, maxVr: float) None ¶
Set the maximal rotation velocity that can be sent to the robot during a velocity control.
- setMaxTranslationVelocity(self, maxVt: float) None ¶
Set the maximal translation velocity that can be sent to the robot during a velocity control.
- setPosition(self, frame: visp._visp.robot.Robot.ControlFrameType, q: visp._visp.core.ColVector) None ¶
- setRobotState(self, newState: visp._visp.robot.Robot.RobotStateType) visp._visp.robot.Robot.RobotStateType ¶
- setVelocity(self, frame: visp._visp.robot.Robot.ControlFrameType, vel: visp._visp.core.ColVector) None ¶
- set_eMc(self, eMc: visp._visp.core.HomogeneousMatrix) None ¶
Set constant transformation between end-effector and tool frame. If your tool is a camera, this transformation is obtained by hand-eye calibration.