SimulatorPioneer¶
- class SimulatorPioneer(self)¶
Bases:
Pioneer
,RobotSimulator
Class that defines the Pioneer mobile robot simulator equipped with a static camera.
It intends to simulate the mobile robot described in vpPioneer class. This robot has 2 dof: \((v_x, w_z)\) , the translational and rotational velocities that are applied at point E.
The robot position evolves with respect to a world frame; wMc. When a new joint velocity is applied to the robot using setVelocity() , the position of the camera wrt the world frame is updated.
<unparsed image <doxmlparser.compound.docImageType object at 0x7f121d432710>>
The following code shows how to control this robot in position and velocity.
#include <visp3/robot/vpSimulatorPioneer.h> #ifdef ENABLE_VISP_NAMESPACE using namespace VISP_NAMESPACE_NAME; #endif int main() { vpHomogeneousMatrix wMc; vpSimulatorPioneer robot; robot.getPosition(wMc); // Position of the camera in the world frame std::cout << "Default position of the camera in the world frame wMc:\n" << wMc << std::endl; robot.setSamplingTime(0.100); // Modify the default sampling time to 0.1 second robot.setMaxTranslationVelocity(1.); // vx max set to 1 m/s robot.setMaxRotationVelocity(vpMath::rad(90)); // wz max set to 90 deg/s vpColVector v(2); // we control vx and wz dof v = 0; v[0] = 1.; // set vx to 1 m/s robot.setVelocity(vpRobot::ARTICULAR_FRAME, v); // The robot has moved from 0.1 meters along the z axis robot.getPosition(wMc); // Position of the camera in the world frame std::cout << "New position of the camera wMc:\n" << wMc << std::endl; }
The usage of this class is also highlighted in tutorial-simu-robot-pioneer.
Constructor.
Methods
Constructor.
Overloaded function.
Get the robot jacobian expressed in the end-effector frame.
Inherited Methods
STATE_VELOCITY_CONTROL
MIXT_FRAME
Return robot degrees of freedom number.
Robot control frames.
REFERENCE_FRAME
STATE_POSITION_CONTROL
Return the sampling time.
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
Set the robot jacobian \({^e}{\bf J}_e\) expressed in the end effector frame.
JOINT_STATE
STATE_STOP
Set the transformation between the camera frame and the end effector frame.
END_EFFECTOR_FRAME
Return the transformation \({^c}{\bf M}_e\) between the camera frame and the mobile robot end effector frame.
ARTICULAR_FRAME
Saturate velocities.
Set the maximal translation velocity that can be sent to the robot during a velocity control.
Overloaded function.
Set the sampling time.
STATE_FORCE_TORQUE_CONTROL
Get the maximal rotation velocity that can be sent to the robot during a velocity control.
Operators
__doc__
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)¶
Constructor.
- 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.SimulatorPioneer, wMc: visp._visp.core.HomogeneousMatrix) -> None
Get the robot position in the world frame.
getPosition(self: visp._visp.robot.SimulatorPioneer, frame: visp._visp.robot.Robot.ControlFrameType, q: visp._visp.core.ColVector) -> None
- getRobotState(self) visp._visp.robot.Robot.RobotStateType ¶
- getSamplingTime(self) float ¶
Return the sampling time.
- Returns:
Sampling time in second used to compute the robot displacement from the velocity applied to the robot during this time.
- get_cMe(self) visp._visp.core.HomogeneousMatrix ¶
Return the transformation \({^c}{\bf M}_e\) between the camera frame and the mobile robot end effector frame.
- get_cVe(*args, **kwargs)¶
Overloaded function.
get_cVe(self: visp._visp.robot.Unicycle) -> visp._visp.core.VelocityTwistMatrix
Return the twist transformation from camera frame to the mobile robot end effector frame. This transformation allows to compute a velocity expressed in the end effector frame into the camera frame.
get_cVe(self: visp._visp.robot.Unicycle, cVe: visp._visp.core.VelocityTwistMatrix) -> None
Return the twist transformation from camera frame to the mobile robot end effector frame. This transformation allows to compute a velocity expressed in the end effector frame into the camera frame.
Note
See get_cVe()
- get_eJe(self, eJe: visp._visp.core.Matrix) None ¶
Get the robot jacobian expressed in the end-effector frame. The jacobian expression is given in vpPioneer class.
- 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.
- 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_cMe(self, cMe: visp._visp.core.HomogeneousMatrix) None ¶
Set the transformation between the camera frame and the end effector frame.
- set_eJe(self, eJe: visp._visp.core.Matrix) None ¶
Set the robot jacobian \({^e}{\bf J}_e\) expressed in the end effector frame.
- Parameters:
- eJe: visp._visp.core.Matrix¶
The robot jacobian to set such as \({\bf v} = {^e}{\bf J}_e \; \dot{\bf q}\) with \(\dot{\bf q} = (v_x, w_z)\) the robot control velocities and \(\bf v\) the six dimension velocity skew.