SimulatorPioneerPan

class SimulatorPioneerPan(self)

Bases: PioneerPan, RobotSimulator

Class that defines the Pioneer mobile robot simulator equipped with a camera able to move in pan.

It intends to simulate the mobile robot described in vpPioneerPan class. This robot has 3 dof: \((v_x, w_z, \dot{q_1})\) , the translational and rotational velocities of the mobile platform, the pan head velocity respectively.

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 0x7ff691a1b580>>

The following code shows how to control this robot in position and velocity.

#include <visp3/robot/vpSimulatorPioneerPan.h>

int main()
{
  vpHomogeneousMatrix wMc;
  vpSimulatorPioneerPan 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(3); // we control vx, wz and q_pan
  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.

Initialise the robot by a call to init() .

Sampling time is set to 40 ms. To change it you should call setSamplingTime() .

Methods

__init__

Constructor.

getPosition

Overloaded function.

get_eJe

Get the robot jacobian expressed in the end-effector frame.

setVelocity

Inherited Methods

STATE_ACCELERATION_CONTROL

RobotStateType

Robot control frames.

setMaxTranslationVelocity

Set the maximal translation velocity that can be sent to the robot during a velocity control.

getRobotState

setVerbose

END_EFFECTOR_FRAME

CAMERA_FRAME

set_eJe

Overloaded function.

saturateVelocities

Saturate velocities.

ARTICULAR_FRAME

JOINT_STATE

TOOL_FRAME

setMaxRotationVelocity

Set the maximal rotation velocity that can be sent to the robot during a velocity control.

getNDof

Return robot degrees of freedom number.

STATE_STOP

set_cMe

Set the transformation between the camera frame and the end effector frame.

STATE_POSITION_CONTROL

getMaxTranslationVelocity

Get the maximal translation velocity that can be sent to the robot during a velocity control.

setRobotState

getSamplingTime

Return the sampling time.

get_cVe

Overloaded function.

ControlFrameType

Robot control frames.

getMaxRotationVelocity

Get the maximal rotation velocity that can be sent to the robot during a velocity control.

REFERENCE_FRAME

get_cMe

Return the transformation \({^c}{\bf M}_e\) between the camera frame and the mobile robot end effector frame.

STATE_FORCE_TORQUE_CONTROL

setSamplingTime

Set the sampling time.

STATE_VELOCITY_CONTROL

MIXT_FRAME

Operators

__doc__

__init__

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.

__and__(self, other: object) object
__eq__(self, other: object) bool
__ge__(self, other: object) bool
__getstate__(self) int
__gt__(self, other: object) bool
__hash__(self) int
__index__(self) int
__init__(self, value: int)
__int__(self) int
__invert__(self) object
__le__(self, other: object) bool
__lt__(self, other: object) bool
__ne__(self, other: object) bool
__or__(self, other: object) object
__rand__(self, other: object) object
__ror__(self, other: object) object
__rxor__(self, other: object) object
__setstate__(self, state: int) None
__xor__(self, other: object) object
property name : str
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.

__and__(self, other: object) object
__eq__(self, other: object) bool
__ge__(self, other: object) bool
__getstate__(self) int
__gt__(self, other: object) bool
__hash__(self) int
__index__(self) int
__init__(self, value: int)
__int__(self) int
__invert__(self) object
__le__(self, other: object) bool
__lt__(self, other: object) bool
__ne__(self, other: object) bool
__or__(self, other: object) object
__rand__(self, other: object) object
__ror__(self, other: object) object
__rxor__(self, other: object) object
__setstate__(self, state: int) None
__xor__(self, other: object) object
property name : str
__init__(self)

Constructor.

Initialise the robot by a call to init() .

Sampling time is set to 40 ms. To change it you should call setSamplingTime() .

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.

getNDof(self) int

Return robot degrees of freedom number.

getPosition(*args, **kwargs)

Overloaded function.

  1. getPosition(self: visp._visp.robot.SimulatorPioneerPan, wMc: visp._visp.core.HomogeneousMatrix) -> None

Get the robot position in the world frame.

  1. getPosition(self: visp._visp.robot.SimulatorPioneerPan, 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.

  1. 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.

  1. 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 vpPioneerPan 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>

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
setSamplingTime(self, delta_t: float) None

Set the sampling time.

Parameters:
delta_t: float

Sampling time in second used to compute the robot displacement from the velocity applied to the robot during this time.

setVelocity(self, frame: visp._visp.robot.Robot.ControlFrameType, vel: visp._visp.core.ColVector) None
setVerbose(self, verbose: bool) None
set_cMe(self, cMe: visp._visp.core.HomogeneousMatrix) None

Set the transformation between the camera frame and the end effector frame.

set_eJe(*args, **kwargs)

Overloaded function.

  1. set_eJe(self: visp._visp.robot.PioneerPan, q_pan: float) -> None

Set the robot jacobian expressed at point E the end effector frame located on the pan head.

Considering \({\bf v} = {^e}{\bf J}_e \; [v_x, w_z, \dot{q_1}]\) with \((v_x, w_z)\) respectively the translational and rotational control velocities of the mobile platform, \(\dot{q_1}\) the joint velocity of the pan head and \(\bf v\) the six dimension velocity skew expressed at point E in frame E, the robot jacobian is given by:

\[\begin{split}{^e}{\bf J}_e = \left(\begin{array}{ccc} c_1 & -c_1*p_y - s_1*p_x & 0 \\0 & 0 & 0 \\s_1 & -s_1*p_y + c_1*p_x & 0 \\0 & 0 & 0 \\0 & -1 & 1 \\0 & 0 & 0 \\\end{array} \right) \end{split}\]

with \(p_x, p_y\) the position of the head base frame in the mobile platform frame located at the middle point between the two wheels.

  1. set_eJe(self: visp._visp.robot.Unicycle, eJe: visp._visp.core.Matrix) -> None

Set the robot jacobian \({^e}{\bf J}_e\) expressed in the end effector frame.

Parameters:
eJe

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.