Skip to content

Commit

Permalink
Fix previous commit
Browse files Browse the repository at this point in the history
  • Loading branch information
fspindle committed Oct 17, 2023
1 parent c0f8538 commit db868e0
Show file tree
Hide file tree
Showing 14 changed files with 209 additions and 255 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -520,7 +520,7 @@ VP_OPTION(USE_PYLON Pylon "" "Include Pylon SDK support for Basle
VP_OPTION(USE_UEYE Ueye "" "Include uEye SDK support for IDS cameras" "" ON IF NOT WINRT AND NOT IOS)
VP_OPTION(USE_COMEDI Comedi "" "Include comedi (linux control and measurement device interface) support" "" ON IF NOT WINRT AND NOT IOS)
VP_OPTION(USE_FTIITSDK FTIITSDK "" "Include IIT force-torque SDK support" "" ON IF NOT WINRT AND NOT IOS)
VP_OPTION(USE_BICLOPS BICLOPS "" "Include biclops support" "" ON IF NOT WINRT AND NOT IOS)
VP_OPTION(USE_BICLOPS BICLOPS "" "Include Biclops support" "" ON IF NOT WINRT AND NOT IOS)
VP_OPTION(USE_PTU46 PTU46 "" "Include ptu-46 support" "" ON IF UNIX AND NOT WINRT AND NOT IOS)
VP_OPTION(USE_FLIRPTUSDK FlirPtuSDK "" "Include Flir PTU SDK support" "" ON IF NOT WINRT AND NOT IOS)
VP_OPTION(USE_CMU1394 CMU1394 "" "Include cmu1494 support" "" ON IF WIN32 AND NOT WINRT AND NOT IOS)
Expand Down
2 changes: 1 addition & 1 deletion ChangeLog.txt
Original file line number Diff line number Diff line change
Expand Up @@ -957,7 +957,7 @@ ViSP 2.6.2 (released July 15, 2012)
To be able to consider other user defined features the compiler should
be compatible with C++ 11 standard.
- Improvements
- Introduce a new Denavit Hartenberg representation of the Biclops head
- Introduce a new Denavit-Hartenberg representation of the Biclops head
in vpBiclops.
- Compatibility with g++ 4.7 and OpenCV 2.3.1, 2.4.0, 2.4.1
- Remove warning detected with Visual C++ /Wall flag
Expand Down
8 changes: 4 additions & 4 deletions example/servo-biclops/moveBiclops.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
* \file moveBiclops.cpp
* \example moveBiclops.cpp
*
* Example of a real robot control, the biclops robot (pan-tilt turret) by
* Example of a real robot control, the Biclops robot (pan-tilt turret) by
* Traclabs. The robot is controlled first in position, then in velocity.
*
* See http://www.traclabs.com/tracbiclops.htm for more details.
Expand Down Expand Up @@ -63,7 +63,7 @@
void usage(const char *name, const char *badparam, std::string conf)
{
fprintf(stdout, "\n\
Move the biclops robot\n\
Move the Biclops robot\n\
\n\
SYNOPSIS\n\
%s [-c <Biclops configuration file>] [-h]\n\
Expand All @@ -73,7 +73,7 @@ name);
fprintf(stdout, "\n\
OPTIONS: Default\n\
-c <Biclops configuration file> %s\n\
Sets the biclops robot configuration file.\n\n",
Sets the Biclops robot configuration file.\n\n",
conf.c_str());

if (badparam) {
Expand Down Expand Up @@ -270,7 +270,7 @@ int main(int argc, const char **argv)
#else
int main()
{
std::cout << "You do not have an biclops PT robot connected to your computer..." << std::endl;
std::cout << "You do not have an Biclops PT robot connected to your computer..." << std::endl;
return EXIT_SUCCESS;
}

Expand Down
6 changes: 3 additions & 3 deletions example/servo-biclops/servoBiclopsPoint2DArtVelocity.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@
* \example servoBiclopsPoint2DArtVelocity.cpp
*
* Example of eye-in-hand control law. We control here a real robot, the
* biclops robot (pan-tilt head provided by Traclabs). The velocity is computed
* Biclops robot (pan-tilt head provided by Traclabs). The velocity is computed
* in articular. The visual feature is the center of gravity of a point.
*/

Expand Down Expand Up @@ -90,7 +90,7 @@ SYNOPSIS\n\
fprintf(stdout, "\n\
OPTIONS: Default\n\
-c <Biclops configuration file> %s\n\
Sets the biclops robot configuration file.\n",
Sets the Biclops robot configuration file.\n",
conf.c_str());

if (badparam) {
Expand Down Expand Up @@ -338,7 +338,7 @@ int main(int argc, const char **argv)
#else
int main()
{
std::cout << "You do not have an biclops PT robot connected to your computer..." << std::endl;
std::cout << "You do not have an Biclops PT robot connected to your computer..." << std::endl;
return EXIT_SUCCESS;
}
#endif
6 changes: 3 additions & 3 deletions example/servo-pioneer/servoPioneerPanSegment3D.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ int main(int argc, char **argv)
double qm_pan = 0; // Measured pan position (tilt is not handled in that example)

#ifdef USE_REAL_ROBOT
// Initialize the biclops head
// Initialize the Biclops head

vpRobotBiclops biclops("/usr/share/BiclopsDefault.cfg");
biclops.setDenavitHartenbergModel(vpBiclops::DH1);
Expand Down Expand Up @@ -158,7 +158,7 @@ int main(int argc, char **argv)
#endif

vpPioneerPan robot_pan; // Generic robot that computes the velocities for
// the pioneer and the biclops head
// the pioneer and the Biclops head

// Camera parameters. In this experiment we don't need a precise
// calibration of the camera
Expand Down Expand Up @@ -379,7 +379,7 @@ int main(int argc, char **argv)

std::cout << "Send velocity to the pionner: " << v_pioneer[0] << " m/s " << vpMath::deg(v_pioneer[1])
<< " deg/s" << std::endl;
std::cout << "Send velocity to the biclops head: " << vpMath::deg(v_biclops[0]) << " deg/s" << std::endl;
std::cout << "Send velocity to the Biclops head: " << vpMath::deg(v_biclops[0]) << " deg/s" << std::endl;

pioneer.setVelocity(vpRobot::REFERENCE_FRAME, v_pioneer);
biclops.setVelocity(vpRobot::ARTICULAR_FRAME, v_biclops);
Expand Down
2 changes: 1 addition & 1 deletion modules/robot/include/visp3/robot/vpAfma4.h
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@ class VISP_EXPORT vpAfma4
static const unsigned int njoint; ///< Number of joint.

protected:
// Denavit Hartenberg parameters
// Denavit-Hartenberg parameters
double _a1; // distance along x2
double _d3; // distance along z2
double _d4; // distance along z3
Expand Down
48 changes: 24 additions & 24 deletions modules/robot/include/visp3/robot/vpBiclops.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@
* \brief Jacobian, geometric model functionalities... for Biclops, pan, tilt
* head.
*
* Two different Denavit Hartenberg representations of the robot are
* Two different Denavit-Hartenberg representations of the robot are
* implemented. As mentioned in vpBiclops::DenavitHartenbergModel they differ
* in the orientation of the tilt axis. Use setDenavitHartenbergModel() to
* select the representation.
Expand All @@ -62,7 +62,7 @@ class VISP_EXPORT vpBiclops
{
public:
/*!
* Two different Denavit Hartenberg representations of the robot are
* Two different Denavit-Hartenberg representations of the robot are
* implemented. As you can see in the next image, they differ in the orientation of the tilt axis.
*
* \image html img-biclops-frames.jpg Biclops PT models
Expand Down Expand Up @@ -91,8 +91,8 @@ class VISP_EXPORT vpBiclops
*/
typedef enum
{
DH1, //!< First Denavit Hartenberg representation.
DH2 //!< Second Denavit Hartenberg representation.
DH1, //!< First Denavit-Hartenberg representation.
DH2 //!< Second Denavit-Hartenberg representation.
} DenavitHartenbergModel;

public:
Expand All @@ -105,12 +105,12 @@ class VISP_EXPORT vpBiclops
static const float speedLimit; //!< Pan and tilt axis max velocity in rad/s to perform a displacement

protected:
DenavitHartenbergModel m_dh_model; //!< Denavit Hartenberg model
vpHomogeneousMatrix m_cMe; //!< Camera frame to end-effector transformation
DenavitHartenbergModel m_dh_model; //!< Denavit-Hartenberg model
vpHomogeneousMatrix m_cMe; //!< Camera frame to PT end-effector frame transformation

public:
/*!
* Default constructor. Call init() that sets vpBiclops::DH1 Denavit Hartenberg model.
* Default constructor. Call init() that sets vpBiclops::DH1 Denavit-Hartenberg model.
*/
vpBiclops(void);

Expand All @@ -124,7 +124,7 @@ class VISP_EXPORT vpBiclops

/*!
* Initialization.
* - By default vpBiclops::DH1 Denavit Hartenberg model is selected.
* - By default vpBiclops::DH1 Denavit-Hartenberg model is selected.
* - Initialize also the default \f${^c}{\bf M}_e\f$ transformation calling set_cMe().
* \f[
* {^c}{\bf M}_e = \left(
Expand Down Expand Up @@ -197,28 +197,28 @@ class VISP_EXPORT vpBiclops
* camera frame and the end effector frame. The end effector frame is located
* on the tilt axis.
*
* \param cVe : Twist transformation between camera and end effector frame to
* \param[out] cVe : Twist transformation between camera and end effector frame to
* express a velocity skew from end effector frame in camera frame.
*/
void get_cVe(vpVelocityTwistMatrix &cVe) const;

/*!
* Compute the direct geometric model of the camera: fMc
*
* \param q : Joint position for pan and tilt axis.
* \param[in] q : Joint position for pan and tilt axis.
*
* \param fMc : Homogeneous matrix corresponding to the direct geometric model
* \param[out] fMc : Homogeneous matrix corresponding to the direct geometric model
* of the camera. Describes the transformation between the robot reference
* frame (called fixed) and the camera frame.
*/
void get_fMc(const vpColVector &q, vpHomogeneousMatrix &fMc) const;

/*!
* Compute the direct geometric model of the camera: fMc
* Compute the direct geometric model of the camera in terms of pose vector.
*
* \param q : Joint position for pan and tilt axis.
* \param[in] q : Joint position for pan and tilt axis.
*
* \param fPc : Pose vector corresponding to the direct geometric model
* \param[out] fPc : Pose vector corresponding to the direct geometric model
* of the camera. Describes the transformation between the robot reference
* frame (called fixed) and the camera frame.
*/
Expand All @@ -227,7 +227,7 @@ class VISP_EXPORT vpBiclops
/*!
* Return the direct geometric model of the camera: fMc
*
* \param q : Joint position for pan and tilt axis.
* \param[in] q : Joint position for pan and tilt axis.
*
* \return fMc, the homogeneous matrix corresponding to the direct geometric
* model of the camera. Describes the transformation between the robot
Expand All @@ -238,7 +238,7 @@ class VISP_EXPORT vpBiclops
/*!
* Return the direct geometric model of the end effector: fMe
*
* \param q : Joint position for pan and tilt axis.
* \param[in] q : Joint position for pan and tilt axis.
*
* \return fMe, the homogeneous matrix corresponding to the direct geometric
* model of the end effector. Describes the transformation between the robot
Expand All @@ -252,25 +252,25 @@ class VISP_EXPORT vpBiclops
* \warning Re is not the embedded camera frame. It corresponds to the frame
* associated to the tilt axis (see also get_cMe).
*
* \param q : Joint position for pan and tilt axis.
* \param[in] q : Joint position for pan and tilt axis.
*
* \param eJe : Jacobian between end effector frame and end effector frame (on
* \param[out] eJe : Jacobian between end effector frame and end effector frame (on
* tilt axis).
*/
void get_eJe(const vpColVector &q, vpMatrix &eJe) const;

/*!
* Get the robot jacobian expressed in the robot reference frame
*
* \param q : Joint position for pan and tilt axis.
* \param[in] q : Joint position for pan and tilt axis.
*
* \param fJe : Jacobian between reference frame (or fix frame) and end
* \param[out] fJe : Jacobian between reference frame (or fix frame) and end
* effector frame (on tilt axis).
*/
void get_fJe(const vpColVector &q, vpMatrix &fJe) const;

/*!
* Return the Denavit Hartenberg representation used to model the head.
* Return the Denavit-Hartenberg representation used to model the head.
* \sa vpBiclops::DenavitHartenbergModel
*/
inline vpBiclops::DenavitHartenbergModel getDenavitHartenbergModel() const { return m_dh_model; }
Expand Down Expand Up @@ -300,9 +300,9 @@ class VISP_EXPORT vpBiclops
void set_cMe(const vpHomogeneousMatrix &cMe) { m_cMe = cMe; }

/*!
* Set the Denavit Hartenberg representation used to model the head.
* Set the Denavit-Hartenberg representation used to model the head.
*
* \param[in] dh_model : Denavit Hartenberg model. \sa vpBiclops::DenavitHartenbergModel
* \param[in] dh_model : Denavit-Hartenberg model. \sa vpBiclops::DenavitHartenbergModel
*/
inline void setDenavitHartenbergModel(vpBiclops::DenavitHartenbergModel dh_model = vpBiclops::DH1)
{
Expand All @@ -315,7 +315,7 @@ class VISP_EXPORT vpBiclops
* Set output stream with Biclops parameters.
* @param os : Output stream.
* @param dummy : Not used.
* @return Output stream with the biclops parameters.
* @return Output stream with the Biclops parameters.
*/
friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpBiclops &dummy);
};
Expand Down
12 changes: 6 additions & 6 deletions modules/robot/include/visp3/robot/vpRobotBiclops.h
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@
* See http://www.traclabs.com/biclopspt.html for more details.
*
* This class provide a position and a speed control interface for the Biclops
* head. To manage the biclops joint limits in speed control, a control loop is
* head. To manage the Biclops joint limits in speed control, a control loop is
* running in a separate thread implemented in vpRobotBiclopsSpeedControlLoop().
*
* \warning Velocity control mode is not exported from the top-level Biclops
Expand Down Expand Up @@ -308,7 +308,7 @@ class VISP_EXPORT vpRobotBiclops : public vpBiclops, public vpRobot
* \warning This method is blocking. That mean that it waits the end of the
* positioning.
*
* \param frame : Control frame. This biclops head can only be controlled in
* \param frame : Control frame. This Biclops head can only be controlled in
* joint state.
*
* \param q : The joint position to set for each axis in radians.
Expand All @@ -324,7 +324,7 @@ class VISP_EXPORT vpRobotBiclops : public vpBiclops, public vpRobot
* \warning This method is blocking. That mean that it wait the end of the
* positioning.
*
* \param frame : Control frame. This biclops head can only be controlled in
* \param frame : Control frame. This Biclops head can only be controlled in
* joint state.
*
* \param q1 : The pan joint position to set in radians.
Expand All @@ -336,8 +336,8 @@ class VISP_EXPORT vpRobotBiclops : public vpBiclops, public vpRobot
void setPosition(const vpRobot::vpControlFrameType frame, const double &q1, const double &q2);

/*!
* Read the content of the position file and moves to head to joint
* position.
* Read the content of the position file and moves the head to joint
* positions.
*
* \param filename : Position filename
*
Expand Down Expand Up @@ -365,7 +365,7 @@ class VISP_EXPORT vpRobotBiclops : public vpBiclops, public vpRobot
/*!
* Send a velocity on each axis.
*
* \param frame : Control frame. This biclops head can only be controlled in
* \param 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.
Expand Down
Loading

0 comments on commit db868e0

Please sign in to comment.