Public Member Functions | Private Member Functions | List of all members
vpROSRobotPioneer Class Reference

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

#include <vpROSRobotPioneer.h>

Inheritance diagram for vpROSRobotPioneer:
Inheritance graph
[legend]

Public Member Functions

void disableMotors ()
 
void enableMotors ()
 
void get_eJe (vpMatrix &eJe)
 
vpColVector getVelocity (const vpRobot::vpControlFrameType frame)
 
void getVelocity (const vpRobot::vpControlFrameType frame, vpColVector &velocity)
 
void init ()
 basic initialization More...
 
void init (int argc, char **argv)
 
void setVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &vel)
 
void useSonar (bool usage)
 
 vpROSRobotPioneer ()
 
 ~vpROSRobotPioneer ()
 destructor More...
 
- Public Member Functions inherited from vpROSRobot
void getDisplacement (const vpRobot::vpControlFrameType, vpColVector &)
 
void getDisplacement (const vpRobot::vpControlFrameType, vpColVector &, struct timespec &timestamp)
 
void getPosition (const vpRobot::vpControlFrameType, vpColVector &)
 
void init ()
 basic initialization More...
 
void init (int argc, char **argv)
 
void setCmdVelTopic (std::string topic_name)
 
void setMasterURI (std::string master_uri)
 
void setNodespace (std::string nodespace)
 
void setOdomTopic (std::string topic_name)
 
void setVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &vel)
 
void stopMotion ()
 
 vpROSRobot ()
 constructor More...
 
virtual ~vpROSRobot ()
 destructor More...
 

Private Member Functions

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

Additional Inherited Members

- Protected Attributes inherited from vpROSRobot
std::string _master_uri
 
std::string _nodespace
 
uint32_t _nsec
 
uint32_t _sec
 
std::string _topic_cmd
 
std::string _topic_odom
 
ros::Publisher cmdvel
 
vpColVector displacement
 
bool isInitialized
 
ros::NodeHandlen
 
ros::Subscriber odom
 
volatile bool odom_mutex
 
vpTranslationVector p
 
vpColVector pose_prev
 
vpQuaternionVector q
 
ros::AsyncSpinnerspinner
 

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

◆ vpROSRobotPioneer() [1/2]

vpROSRobotPioneer::vpROSRobotPioneer ( )

Default constructor that initializes Aria.

Definition at line 51 of file vpROSRobotPioneer.cpp.

◆ ~vpROSRobotPioneer()

vpROSRobotPioneer::~vpROSRobotPioneer ( )

destructor

Definition at line 57 of file vpROSRobotPioneer.cpp.

◆ vpROSRobotPioneer() [2/2]

vpROSRobotPioneer::vpROSRobotPioneer ( const vpROSRobotPioneer robot)
private

Copy constructor not allowed.

Member Function Documentation

◆ disableMotors()

void vpROSRobotPioneer::disableMotors ( )

Definition at line 145 of file vpROSRobotPioneer.cpp.

◆ enableMotors()

void vpROSRobotPioneer::enableMotors ( )

Definition at line 134 of file vpROSRobotPioneer.cpp.

◆ get_eJe()

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()
Examples
tutorial-ros-pioneer-visual-servo.cpp, and tutorial_ros_node_pioneer_visual_servo.cpp.

Definition at line 84 of file vpROSRobotPioneer.h.

◆ get_fJe()

void vpROSRobotPioneer::get_fJe ( vpMatrix &  )
inlineprivate

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

Warning
Not implemented.

Definition at line 120 of file vpROSRobotPioneer.h.

◆ getVelocity() [1/2]

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

Definition at line 90 of file vpROSRobotPioneer.h.

◆ getVelocity() [2/2]

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

Definition at line 86 of file vpROSRobotPioneer.h.

◆ init() [1/2]

void vpROSRobotPioneer::init ( )

◆ init() [2/2]

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

Definition at line 72 of file vpROSRobotPioneer.cpp.

◆ setPosition()

void vpROSRobotPioneer::setPosition ( const vpRobot::vpControlFrameType  ,
const vpColVector &   
)
inlineprivate

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

Warning
Not implemented.

Definition at line 126 of file vpROSRobotPioneer.h.

◆ setVelocity()

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.
Examples
tutorial-ros-pioneer-visual-servo.cpp, tutorial-ros-pioneer.cpp, and tutorial_ros_node_pioneer_visual_servo.cpp.

Definition at line 96 of file vpROSRobotPioneer.cpp.

◆ useSonar()

void vpROSRobotPioneer::useSonar ( bool  usage)
inline

Enable or disable sonar device usage.

Definition at line 104 of file vpROSRobotPioneer.h.


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


visp_ros
Author(s): Francois Pasteau, Fabien Spindler, Gatien Gaumerais, Alexander Oliva
autogenerated on Wed Mar 2 2022 01:13:33