Public Member Functions | Private Member Functions
vpROSRobotPioneer Class Reference

Interface for Pioneer mobile robots based on ROS. More...

#include <vpROSRobotPioneer.h>

Inheritance diagram for vpROSRobotPioneer:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void disableMotors ()
void enableMotors ()
void get_eJe (vpMatrix &eJe)
void getVelocity (const vpRobot::vpControlFrameType frame, vpColVector &velocity)
vpColVector getVelocity (const vpRobot::vpControlFrameType frame)
void init ()
 basic initialization
void init (int argc, char **argv)
void setVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &vel)
void useSonar (bool usage)
 vpROSRobotPioneer ()
 ~vpROSRobotPioneer ()
 destructor

Private Member Functions

void get_fJe (vpMatrix &)
void setPosition (const vpRobot::vpControlFrameType, const vpColVector &)
 vpROSRobotPioneer (const vpROSRobotPioneer &robot)

Detailed Description

Interface for Pioneer mobile robots based on ROS.

This class provides a position and speed control interface for Pioneer mobile robots. It inherits from the vpROSRobot class. For more information about the model of the robot, see vpPioneer documentation on ViSP website http:://team.inria.fr/visp.

Examples:
tutorial-ros-pioneer-visual-servo.cpp, tutorial-ros-pioneer.cpp, and tutorial_ros_node_pioneer_visual_servo.cpp.

Definition at line 64 of file vpROSRobotPioneer.h.


Constructor & Destructor Documentation

Default constructor that initializes Aria.

Definition at line 52 of file vpROSRobotPioneer.cpp.

destructor

Definition at line 58 of file vpROSRobotPioneer.cpp.

Copy constructor not allowed.


Member Function Documentation

Definition at line 143 of file vpROSRobotPioneer.cpp.

Definition at line 133 of file vpROSRobotPioneer.cpp.

void vpROSRobotPioneer::get_eJe ( vpMatrix &  eJe) [inline]

Get the robot Jacobian expressed at point E, the point located at the middle between the two wheels.

Parameters:
eJe: Robot jacobian such as $(v_x, w_z) = {^e}{\bf J}e \; {\bf v}$ with $(v_x, w_z)$ respectively the translational and rotational control velocities of the mobile robot, $\bf v$ the six dimention velocity skew, and where
See also:
get_eJe()

Reimplemented from vpROSRobot.

Examples:
tutorial-ros-pioneer-visual-servo.cpp, and tutorial_ros_node_pioneer_visual_servo.cpp.

Definition at line 84 of file vpROSRobotPioneer.h.

void vpROSRobotPioneer::get_fJe ( vpMatrix &  ) [inline, private]

Get the robot Jacobian expressed in the robot reference (or world) frame.

Warning:
Not implemented.

Reimplemented from vpROSRobot.

Definition at line 124 of file vpROSRobotPioneer.h.

void vpROSRobotPioneer::getVelocity ( const vpRobot::vpControlFrameType  frame,
vpColVector &  velocity 
) [inline]

Reimplemented from vpROSRobot.

Definition at line 89 of file vpROSRobotPioneer.h.

vpColVector vpROSRobotPioneer::getVelocity ( const vpRobot::vpControlFrameType  frame) [inline]

Reimplemented from vpROSRobot.

Definition at line 93 of file vpROSRobotPioneer.h.

basic initialization

Reimplemented from vpROSRobot.

Examples:
tutorial-ros-pioneer-visual-servo.cpp, tutorial-ros-pioneer.cpp, and tutorial_ros_node_pioneer_visual_servo.cpp.

Definition at line 65 of file vpROSRobotPioneer.cpp.

void vpROSRobotPioneer::init ( int  argc,
char **  argv 
)

Basic initialisation

Parameters:
argc,argv: parameters of the main function

Reimplemented from vpROSRobot.

Definition at line 71 of file vpROSRobotPioneer.cpp.

void vpROSRobotPioneer::setPosition ( const vpRobot::vpControlFrameType  ,
const vpColVector &   
) [inline, private]

Set a displacement (frame has to be specified) in position control.

Warning:
Not implemented.

Reimplemented from vpROSRobot.

Definition at line 130 of file vpROSRobotPioneer.h.

void vpROSRobotPioneer::setVelocity ( const vpRobot::vpControlFrameType  frame,
const vpColVector &  vel 
)

Set the velocity (frame has to be specified) that will be applied to the robot.

Parameters:
frame: Control frame. For the moment, only vpRobot::REFERENCE_FRAME to control translational and rotational velocities is implemented.
vel: A two dimension vector that corresponds to the velocities to apply to the robot.
  • If the frame is vpRobot::REFERENCE_FRAME, first value is the translation velocity in m/s. Second value is the rotational velocity in rad/s.

Note that to secure the usage of the robot, velocities are saturated to the maximum allowed which can be obtained by getMaxTranslationVelocity() and getMaxRotationVelocity(). To change the default values, use setMaxTranslationVelocity() and setMaxRotationVelocity().

Exceptions:
vpRobotException::dimensionError: Velocity vector is not a 2 dimension vector.
vpRobotException::wrongStateError: If the specified control frame is not supported.

Reimplemented from vpROSRobot.

Examples:
tutorial-ros-pioneer-visual-servo.cpp, tutorial-ros-pioneer.cpp, and tutorial_ros_node_pioneer_visual_servo.cpp.

Definition at line 94 of file vpROSRobotPioneer.cpp.

void vpROSRobotPioneer::useSonar ( bool  usage) [inline]

Enable or disable sonar device usage.

Definition at line 107 of file vpROSRobotPioneer.h.


The documentation for this class was generated from the following files:


visp_ros
Author(s): Francois Pasteau, Fabien Spindler
autogenerated on Thu Jun 6 2019 18:06:25