39 #include <visp3/core/vpConfig.h>
41 #include <visp3/robot/vpRobotException.h>
48 #include <visp3/core/vpHomogeneousMatrix.h>
49 #include <visp3/robot/vpRobotTemplate.h>
93 std::cout <<
"Not implemented ! " << std::endl;
104 std::cout <<
"Not implemented ! " << std::endl;
128 "Cannot send a velocity twist vector in tool frame that is not 6-dim (%d)", v.
size()));
174 std::cout <<
"Not implemented ! " << std::endl;
175 std::cout <<
"To implement me you need : " << std::endl;
176 std::cout <<
"\t to known the robot jacobian expressed in ";
177 std::cout <<
"the end-effector frame (eJe) " << std::endl;
178 std::cout <<
"\t the frame transformation between tool or camera frame ";
179 std::cout <<
"and end-effector frame (cMe)" << std::endl;
192 std::cout <<
"Not implemented ! " << std::endl;
208 "Cannot send a velocity to the robot. "
209 "Call setRobotState(vpRobot::STATE_VELOCITY_CONTROL) once before "
210 "entering your control loop.");
222 if (vel.
size() != 6) {
224 "Cannot apply a Cartesian velocity that is not a 6-dim vector (%d)", vel.
size()));
228 for (
unsigned int i = 0; i < 3; i++)
230 for (
unsigned int i = 3; i < 6; i++)
240 if (vel.
size() !=
static_cast<size_t>(
nDof)) {
270 std::cout <<
"Not implemented ! " << std::endl;
284 std::cout <<
"Not implemented ! " << std::endl;
298 std::cout <<
"Not implemented ! " << std::endl;
311 std::cout <<
"Not implemented ! " << std::endl;
unsigned int size() const
Return the number of elements of the 2D array.
Implementation of column vector and the associated operations.
error that can be emited by ViSP classes.
@ dimensionError
Bad dimension.
Implementation of a matrix and operations on matrices.
Error that can be emited by the vpRobot class and its derivates.
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q)
void get_eJe(vpMatrix &eJe_)
void get_fJe(vpMatrix &fJe_)
void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &q)
void getJointPosition(vpColVector &q)
void setCartVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &v)
vpHomogeneousMatrix m_eMc
Constant transformation between end-effector and tool (or camera) frame.
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q)
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
virtual ~vpRobotTemplate()
void setJointVelocity(const vpColVector &qdot)
int nDof
number of degrees of freedom
static const double maxTranslationVelocityDefault
virtual vpRobotStateType getRobotState(void) const
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
static const double maxRotationVelocityDefault
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
double getMaxRotationVelocity(void) const
double maxTranslationVelocity
double getMaxTranslationVelocity(void) const
double maxRotationVelocity