Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpRobotPololuPtu Class Reference

#include <vpRobotPololuPtu.h>

Inheritance diagram for vpRobotPololuPtu:

Public Types

enum  vpRobotStateType {
  STATE_STOP , STATE_VELOCITY_CONTROL , STATE_POSITION_CONTROL , STATE_ACCELERATION_CONTROL ,
  STATE_FORCE_TORQUE_CONTROL
}
enum  vpControlFrameType {
  REFERENCE_FRAME , ARTICULAR_FRAME , JOINT_STATE = ARTICULAR_FRAME , END_EFFECTOR_FRAME ,
  CAMERA_FRAME , TOOL_FRAME = CAMERA_FRAME , MIXT_FRAME
}

Public Member Functions

 vpRobotPololuPtu (const std::string &device="/dev/ttyACM0", int baudrate=9600, bool verbose=false)
 ~vpRobotPololuPtu () VP_OVERRIDE
void get_eJe (vpMatrix &eJe) VP_OVERRIDE
void get_eJe (const vpColVector &q, vpMatrix &eJe) const
void get_fJe (vpMatrix &fJe) VP_OVERRIDE
void get_fJe (const vpColVector &q, vpMatrix &fJe) const
float getAngularVelocityResolution () const
void getPosition (const vpRobot::vpControlFrameType frame, vpColVector &q) VP_OVERRIDE
float getPositioningVelocityPercentage () const
void setPosition (const vpRobot::vpControlFrameType frame, const vpColVector &q) VP_OVERRIDE
void setPositioningVelocityPercentage (float positioning_velocity_percentage)
void setVerbose (bool verbose)
void setVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &q_dot) VP_OVERRIDE
void stopVelocity ()
vpRobot::vpRobotStateType setRobotState (const vpRobot::vpRobotStateType newState) VP_OVERRIDE
Inherited functionalities from vpRobot
double getMaxTranslationVelocity (void) const
double getMaxRotationVelocity (void) const
int getNDof () const
vpColVector getPosition (const vpRobot::vpControlFrameType frame)
virtual vpRobotStateType getRobotState (void) const
void setMaxRotationVelocity (double maxVr)
void setMaxTranslationVelocity (double maxVt)

Static Public Member Functions

Static Public Member Functions inherited from vpRobot
static vpColVector saturateVelocities (const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)

Protected Member Functions

Protected Member Functions Inherited from vpRobot
vpControlFrameType setRobotFrame (vpRobot::vpControlFrameType newFrame)
vpControlFrameType getRobotFrame (void) const

Protected Attributes

double maxTranslationVelocity
double maxRotationVelocity
int nDof
vpMatrix eJe
int eJeAvailable
vpMatrix fJe
int fJeAvailable
int areJointLimitsAvailable
double * qmin
double * qmax
bool verbose_

Static Protected Attributes

static const double maxTranslationVelocityDefault = 0.2
static const double maxRotationVelocityDefault = 0.7

Detailed Description

Interface for the Pololu Maestro pan-tilt unit using two servo motors.

See https://www.pololu.com/category/102/maestro-usb-servo-controllers for more details.

This class handle the vpPololu class in a higher level and allows to control the pan-tilt unit using position or velocity commands.

The corresponding Denavit-Hartenberg representations of the PTU is the following:

Joint $a_i$ $d_i$ $\alpha_i$ $\theta_i$
1 0 0 $ \pi/2$ $q_1$
2 0 0 $-\pi/2$ $q_2 - \pi/2$
Examples
servoPololuPtuPoint2DJointVelocity.cpp.

Definition at line 63 of file vpRobotPololuPtu.h.

Member Enumeration Documentation

◆ vpControlFrameType

Robot control frames.

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

Definition at line 73 of file vpRobot.h.

◆ vpRobotStateType

enum vpRobot::vpRobotStateType
inherited

Robot control states.

Enumerator
STATE_STOP 

Stops robot motion especially in velocity and acceleration control.

STATE_VELOCITY_CONTROL 

Initialize the velocity controller.

STATE_POSITION_CONTROL 

Initialize the position controller.

STATE_ACCELERATION_CONTROL 

Initialize the acceleration controller.

STATE_FORCE_TORQUE_CONTROL 

Initialize the force/torque controller.

Definition at line 61 of file vpRobot.h.

Constructor & Destructor Documentation

◆ vpRobotPololuPtu()

BEGIN_VISP_NAMESPACE vpRobotPololuPtu::vpRobotPololuPtu ( const std::string & device = "/dev/ttyACM0",
int baudrate = 9600,
bool verbose = false )

Default constructor.

Parameters
[in]device: Name of the serial interface used for communication.
[in]baudrate: Baudrate used for the serial communication. Note that this parameter is only used on Windows.
[in]verbose: When true, enable verbose mode.

Definition at line 44 of file vpRobotPololuPtu.cpp.

References vpRobot::nDof, and vpMath::rad().

◆ ~vpRobotPololuPtu()

vpRobotPololuPtu::~vpRobotPololuPtu ( )

Destructor that stops the movements.

Definition at line 59 of file vpRobotPololuPtu.cpp.

Member Function Documentation

◆ get_eJe() [1/2]

void vpRobotPololuPtu::get_eJe ( const vpColVector & q,
vpMatrix & eJe ) const

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

Warning
End-effector frame is not the embedded camera frame. It corresponds to the frame associated to the tilt axis (see also get_cMe).
Parameters
[in]q: Joint positions to consider [rad].
[out]eJe: Jacobian between end effector frame and end effector frame (on tilt axis).

Definition at line 81 of file vpRobotPololuPtu.cpp.

References vpException::dimensionError, vpRobot::eJe, vpRobot::nDof, and vpArray2D< Type >::size().

◆ get_eJe() [2/2]

void vpRobotPololuPtu::get_eJe ( vpMatrix & eJe)
virtual

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

Warning
End-effector frame is not the embedded camera frame. It corresponds to the frame associated to the tilt axis (see also get_cMe).
Parameters
[out]eJe: Jacobian between end effector frame and end effector frame (on tilt axis).

Implements vpRobot.

Definition at line 65 of file vpRobotPololuPtu.cpp.

References vpRobot::eJe, get_eJe(), getPosition(), vpRobot::JOINT_STATE, and vpRobot::nDof.

Referenced by get_eJe().

◆ get_fJe() [1/2]

void vpRobotPololuPtu::get_fJe ( const vpColVector & q,
vpMatrix & fJe ) const

Get the robot jacobian expressed in the robot reference frame.

Parameters
[in]q: Joint positions to consider [rad].
[out]fJe: Jacobian between reference frame (or fix frame) and end effector frame (on tilt axis).

Definition at line 99 of file vpRobotPololuPtu.cpp.

References vpException::dimensionError, vpRobot::fJe, vpRobot::nDof, and vpArray2D< Type >::size().

◆ get_fJe() [2/2]

void vpRobotPololuPtu::get_fJe ( vpMatrix & fJe)
virtual

Get the robot jacobian expressed in the robot reference frame.

Parameters
[out]fJe: Jacobian between reference frame (or fix frame) and end effector frame (on tilt axis).

Implements vpRobot.

Definition at line 73 of file vpRobotPololuPtu.cpp.

References vpRobot::fJe, get_fJe(), getPosition(), vpRobot::JOINT_STATE, and vpRobot::nDof.

Referenced by get_fJe().

◆ getAngularVelocityResolution()

float vpRobotPololuPtu::getAngularVelocityResolution ( ) const

Return the minimul angular velocity in rad/s that could be applied to move the motors. It corresponds to 1 pwm converted in rad/s.

Definition at line 117 of file vpRobotPololuPtu.cpp.

◆ getMaxRotationVelocity()

◆ getMaxTranslationVelocity()

◆ getNDof()

int vpRobot::getNDof ( ) const
inlineinherited

Return robot degrees of freedom number.

Definition at line 142 of file vpRobot.h.

References nDof.

◆ getPosition() [1/2]

vpColVector vpRobot::getPosition ( const vpRobot::vpControlFrameType frame)
inherited

Return the current robot position in the specified frame.

Definition at line 215 of file vpRobot.cpp.

References getPosition().

◆ getPosition() [2/2]

void vpRobotPololuPtu::getPosition ( const vpRobot::vpControlFrameType frame,
vpColVector & q )
virtual

Return the position of each joint.

Parameters
[in]frame: Control frame. This PTU can only be controlled in joint state.
[out]q: The position of the joints in radians.
Exceptions
vpRobotException::wrongStateError: If a not supported frame type is given.

Implements vpRobot.

Definition at line 262 of file vpRobotPololuPtu.cpp.

References vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobot::JOINT_STATE, vpRobot::MIXT_FRAME, vpRobot::nDof, vpRobot::REFERENCE_FRAME, vpColVector::resize(), and vpRobotException::wrongStateError.

Referenced by get_eJe(), and get_fJe().

◆ getPositioningVelocityPercentage()

float vpRobotPololuPtu::getPositioningVelocityPercentage ( ) const
inline

Get the percentage of the maximum velocity applied to move the PTU in position.

Returns
Positioning velocity percentage in [0, 100.0]. The maximum positioning velocity is given vpRobot::getMaxRotationVelocity().
See also
setPositioningVelocityPercentage()

Definition at line 149 of file vpRobotPololuPtu.h.

◆ getRobotFrame()

vpControlFrameType vpRobot::getRobotFrame ( void ) const
inlineprotectedinherited

◆ getRobotState()

virtual vpRobotStateType vpRobot::getRobotState ( void ) const
inlinevirtualinherited

Definition at line 152 of file vpRobot.h.

Referenced by vpRobotBiclops::getPosition(), vpRobotBiclops::getVelocity(), vpRobotAfma6::setPosition(), vpRobotBiclops::setPosition(), vpRobotCamera::setPosition(), vpRobotFranka::setPosition(), vpRobotPololuPtu::setPosition(), vpRobotPtu46::setPosition(), vpRobotUniversalRobots::setPosition(), vpRobotViper650::setPosition(), vpRobotViper850::setPosition(), vpSimulatorAfma6::setPosition(), vpSimulatorCamera::setPosition(), vpSimulatorViper850::setPosition(), vpRobotAfma6::setRobotState(), vpRobotBiclops::setRobotState(), vpRobotFlirPtu::setRobotState(), vpRobotFranka::setRobotState(), vpRobotPololuPtu::setRobotState(), vpRobotPtu46::setRobotState(), vpRobotUniversalRobots::setRobotState(), vpRobotViper650::setRobotState(), vpRobotViper850::setRobotState(), vpSimulatorAfma6::setRobotState(), vpSimulatorViper850::setRobotState(), vpRobotAfma6::setVelocity(), vpRobotBiclops::setVelocity(), vpRobotCamera::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotPololuPtu::setVelocity(), vpRobotPtu46::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotFlirPtu::stopMotion(), vpRobotFranka::stopMotion(), vpRobotViper650::stopMotion(), vpRobotViper850::stopMotion(), vpSimulatorAfma6::stopMotion(), and vpSimulatorViper850::stopMotion().

◆ saturateVelocities()

vpColVector vpRobot::saturateVelocities ( const vpColVector & v_in,
const vpColVector & v_max,
bool verbose = false )
staticinherited

Saturate velocities.

Parameters
v_in: Vector of input velocities to saturate. Translation velocities should be expressed in m/s while rotation velocities in rad/s.
v_max: Vector of maximal allowed velocities. Maximal translation velocities should be expressed in m/s while maximal rotation velocities in rad/s.
verbose: Print a message indicating which axis causes the saturation.
Returns
Saturated velocities.
Exceptions
vpRobotException::dimensionError: If the input vectors have different dimensions.

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
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;
}
Implementation of column vector and the associated operations.
vpRowVector t() const
static double rad(double deg)
Definition vpMath.h:129
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition vpRobot.cpp:162

Definition at line 162 of file vpRobot.cpp.

References vpException::dimensionError, and vpArray2D< Type >::size().

Referenced by vpRobotAfma6::setVelocity(), vpRobotCamera::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotPioneer::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), and vpSimulatorPioneerPan::setVelocity().

◆ setMaxRotationVelocity()

void vpRobot::setMaxRotationVelocity ( double w_max)
inherited

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

Parameters
w_max: Maximum rotational velocity expressed in rad/s.
Examples
servoMomentPoints.cpp.

Definition at line 259 of file vpRobot.cpp.

References maxRotationVelocity.

Referenced by init(), vpRobotViper650::setMaxRotationVelocity(), vpRobotViper850::setMaxRotationVelocity(), and vpSimulatorAfma6::setPosition().

◆ setMaxTranslationVelocity()

void vpRobot::setMaxTranslationVelocity ( double v_max)
inherited

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

Parameters
v_max: Maximum translation velocity expressed in m/s.
Examples
servoMomentPoints.cpp.

Definition at line 238 of file vpRobot.cpp.

References maxTranslationVelocity.

Referenced by init(), and vpSimulatorAfma6::setPosition().

◆ setPosition()

void vpRobotPololuPtu::setPosition ( const vpRobot::vpControlFrameType frame,
const vpColVector & q )
virtual

Move the robot to a given joint position.

Warning
This method is blocking. That mean that it waits the end of the positioning.
Parameters
[in]frame: Control frame. This PTU can only be controlled in joint state.
[in]q: The joint position to set for each axis in radians.
Exceptions
vpRobotException::wrongStateError: If a not supported frame type is given.

Implements vpRobot.

Definition at line 122 of file vpRobotPololuPtu.cpp.

References vpRobot::CAMERA_FRAME, vpException::dimensionError, vpRobot::END_EFFECTOR_FRAME, vpRobot::getMaxRotationVelocity(), vpRobot::getRobotState(), vpRobot::JOINT_STATE, vpRobot::MIXT_FRAME, vpRobot::nDof, vpRobot::REFERENCE_FRAME, setRobotState(), vpArray2D< Type >::size(), vpRobot::STATE_POSITION_CONTROL, and vpRobotException::wrongStateError.

◆ setPositioningVelocityPercentage()

void vpRobotPololuPtu::setPositioningVelocityPercentage ( float positioning_velocity_percentage)
inline

Set the percentage of the maximum velocity applied to move the PTU in position.

Parameters
[in]positioning_velocity_percentage: Percentage between [0,100] of the maximum velocity. The maximum positioning velocity is given vpRobot::getMaxRotationVelocity().
See also
getPositioningVelocityPercentage()

Definition at line 178 of file vpRobotPololuPtu.h.

◆ setRobotFrame()

◆ setRobotState()

vpRobot::vpRobotStateType vpRobotPololuPtu::setRobotState ( const vpRobot::vpRobotStateType newState)
virtual

Change the state of the robot either to stop them, or to set position or speed control.

Reimplemented from vpRobot.

Definition at line 230 of file vpRobotPololuPtu.cpp.

References vpRobot::getRobotState(), vpRobot::setRobotState(), vpRobot::STATE_POSITION_CONTROL, vpRobot::STATE_STOP, vpRobot::STATE_VELOCITY_CONTROL, and stopVelocity().

Referenced by setPosition().

◆ setVelocity()

void vpRobotPololuPtu::setVelocity ( const vpRobot::vpControlFrameType frame,
const vpColVector & q_dot )
virtual

Send a velocity on each axis.

Parameters
[in]frame: Control frame. This Biclops head can only be controlled in joint state. Be aware, the camera frame (vpRobot::CAMERA_FRAME), the reference frame (vpRobot::REFERENCE_FRAME), end-effector frame (vpRobot::END_EFFECTOR_FRAME) and the mixt frame (vpRobot::MIXT_FRAME) are not implemented.
[in]q_dot: The desired joint velocities for each axis in rad/s. $ \dot
{r} = [\dot{q}_1, \dot{q}_2]^t $ with $ \dot{q}_1 $ the pan of the camera and $ \dot{q}_2$ the tilt of the camera.
Exceptions
vpRobotException::wrongStateError: If a the robot is not configured to handle a velocity. The robot can handle a velocity only if the velocity control mode is set. For that, call setRobotState( vpRobot::STATE_VELOCITY_CONTROL) before setVelocity().
vpRobotException::wrongStateError: If a not supported frame type (vpRobot::CAMERA_FRAME, vpRobot::REFERENCE_FRAME, vpRobot::END_EFFECTOR_FRAME or vpRobot::MIXT_FRAME) is given.
Warning
Velocities could be saturated if one of them exceed the maximal authorized speed (see vpRobot::maxRotationVelocity).

Implements vpRobot.

Definition at line 155 of file vpRobotPololuPtu.cpp.

References vpRobot::CAMERA_FRAME, vpException::dimensionError, vpRobot::END_EFFECTOR_FRAME, vpRobot::getMaxRotationVelocity(), vpRobot::getRobotState(), vpArray2D< Type >::getRows(), vpRobot::JOINT_STATE, vpRobot::MIXT_FRAME, vpRobot::nDof, vpRobot::REFERENCE_FRAME, vpArray2D< Type >::size(), vpRobot::STATE_VELOCITY_CONTROL, vpColVector::t(), vpERROR_TRACE, and vpRobotException::wrongStateError.

◆ setVerbose()

void vpRobotPololuPtu::setVerbose ( bool verbose)
inline

Enable/disable verbose mode.

Parameters
[in]verbose: Set to true to enable verbose mode, false otherwise.

Definition at line 188 of file vpRobotPololuPtu.h.

◆ stopVelocity()

void vpRobotPololuPtu::stopVelocity ( )

Stop the velocity command.

Definition at line 256 of file vpRobotPololuPtu.cpp.

Referenced by setRobotState().

Member Data Documentation

◆ areJointLimitsAvailable

int vpRobot::areJointLimitsAvailable
protectedinherited

Definition at line 111 of file vpRobot.h.

Referenced by operator=(), vpRobot(), and vpRobot().

◆ eJe

◆ eJeAvailable

int vpRobot::eJeAvailable
protectedinherited

is the robot Jacobian expressed in the end-effector frame available

Definition at line 105 of file vpRobot.h.

Referenced by operator=(), vpRobot(), and vpRobot().

◆ fJe

◆ fJeAvailable

int vpRobot::fJeAvailable
protectedinherited

is the robot Jacobian expressed in the robot reference frame available

Definition at line 109 of file vpRobot.h.

Referenced by operator=(), vpRobot(), and vpRobot().

◆ maxRotationVelocity

◆ maxRotationVelocityDefault

const double vpRobot::maxRotationVelocityDefault = 0.7
staticprotectedinherited

◆ maxTranslationVelocity

double vpRobot::maxTranslationVelocity
protectedinherited

◆ maxTranslationVelocityDefault

BEGIN_VISP_NAMESPACE const double vpRobot::maxTranslationVelocityDefault = 0.2
staticprotectedinherited

◆ nDof

◆ qmax

double* vpRobot::qmax
protectedinherited

Definition at line 113 of file vpRobot.h.

Referenced by operator=(), vpRobot(), vpRobot(), and ~vpRobot().

◆ qmin

double* vpRobot::qmin
protectedinherited

Definition at line 112 of file vpRobot.h.

Referenced by operator=(), vpRobot(), vpRobot(), and ~vpRobot().

◆ verbose_