Interface for Pioneer mobile robots based on ROS. More...
#include <vpROSRobotPioneer.h>
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 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 ×tamp) |
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::NodeHandle * | n |
ros::Subscriber | odom |
volatile bool | odom_mutex |
vpTranslationVector | p |
vpColVector | pose_prev |
vpQuaternionVector | q |
ros::AsyncSpinner * | spinner |
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.
Definition at line 64 of file vpROSRobotPioneer.h.
vpROSRobotPioneer::vpROSRobotPioneer | ( | ) |
Default constructor that initializes Aria.
Definition at line 51 of file vpROSRobotPioneer.cpp.
vpROSRobotPioneer::~vpROSRobotPioneer | ( | ) |
destructor
Definition at line 57 of file vpROSRobotPioneer.cpp.
|
private |
Copy constructor not allowed.
void vpROSRobotPioneer::disableMotors | ( | ) |
Definition at line 145 of file vpROSRobotPioneer.cpp.
void vpROSRobotPioneer::enableMotors | ( | ) |
Definition at line 134 of file vpROSRobotPioneer.cpp.
|
inline |
Get the robot Jacobian expressed at point E, the point located at the middle between the two wheels.
eJe | : Robot jacobian such as with respectively the translational and rotational control velocities of the mobile robot, the six dimention velocity skew, and where |
Definition at line 84 of file vpROSRobotPioneer.h.
|
inlineprivate |
Get the robot Jacobian expressed in the robot reference (or world) frame.
Definition at line 120 of file vpROSRobotPioneer.h.
|
inline |
Definition at line 86 of file vpROSRobotPioneer.h.
|
inline |
Definition at line 90 of file vpROSRobotPioneer.h.
void vpROSRobotPioneer::init | ( | ) |
basic initialization
Definition at line 65 of file vpROSRobotPioneer.cpp.
void vpROSRobotPioneer::init | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 72 of file vpROSRobotPioneer.cpp.
|
inlineprivate |
Set a displacement (frame has to be specified) in position control.
Definition at line 126 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.
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.
|
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().
vpRobotException::dimensionError | : Velocity vector is not a 2 dimension vector. |
vpRobotException::wrongStateError | : If the specified control frame is not supported. |
Definition at line 96 of file vpROSRobotPioneer.cpp.
|
inline |
Enable or disable sonar device usage.
Definition at line 104 of file vpROSRobotPioneer.h.