visual-tracking-control
Public Member Functions | Protected Types | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
VisualServoingServer Class Reference

#include <VisualServoingServer.h>

Inheritance diagram for VisualServoingServer:
[legend]

Public Member Functions

 VisualServoingServer ()
 
 ~VisualServoingServer ()
 
bool open (yarp::os::Searchable &config) override
 
bool close () override
 
bool initFacilities (const bool use_direct_kin) override
 
bool resetFacilities () override
 
bool stopFacilities () override
 
bool goToGoal (const yarp::sig::Vector &vec_x, const yarp::sig::Vector &vec_o) override
 
bool goToGoal (const std::vector< yarp::sig::Vector > &vec_px_l, const std::vector< yarp::sig::Vector > &vec_px_r) override
 
bool setModality (const std::string &mode) override
 
bool setVisualServoControl (const std::string &control) override
 
bool setControlPoint (const yarp::os::ConstString &point) override
 
bool getVisualServoingInfo (yarp::os::Bottle &info) override
 
bool setGoToGoalTolerance (const double tol=15.0) override
 
bool checkVisualServoingController () override
 
bool waitVisualServoingDone (const double period=0.1, const double timeout=0.0) override
 
bool stopController () override
 
bool setTranslationGain (const double K_x_1=1.0, const double K_x_2=0.25) override
 
bool setMaxTranslationVelocity (const double max_x_dot) override
 
bool setTranslationGainSwitchTolerance (const double K_x_tol=30.0) override
 
bool setOrientationGain (const double K_x_1=1.5, const double K_x_2=0.375) override
 
bool setMaxOrientationVelocity (const double max_o_dot) override
 
bool setOrientationGainSwitchTolerance (const double K_o_tol=30.0) override
 
std::vector< yarp::sig::Vector > get3DGoalPositionsFrom3DPose (const yarp::sig::Vector &x, const yarp::sig::Vector &o) override
 
std::vector< yarp::sig::Vector > getGoalPixelsFrom3DPose (const yarp::sig::Vector &x, const yarp::sig::Vector &o, const CamSel &cam) override
 
bool storedInit (const std::string &label) override
 
bool storedGoToGoal (const std::string &label) override
 
bool goToSFMGoal () override
 
virtual bool go_to_px_goal (const std::vector< std::vector< double > > &vec_px_l, const std::vector< std::vector< double > > &vec_px_r)
 Set the goal points on both left and right camera image plane and start visual servoing. More...
 
virtual bool read (yarp::os::ConnectionReader &connection) override
 
virtual std::vector< std::string > help (const std::string &functionName="--all")
 

Protected Types

enum  VisualServoControl { VisualServoControl::decoupled, VisualServoControl::robust, VisualServoControl::cartesian }
 
enum  PixelControlMode { PixelControlMode::all, PixelControlMode::x, PixelControlMode::o }
 
enum  OperatingMode { OperatingMode::position, OperatingMode::orientation, OperatingMode::pose }
 

Protected Member Functions

void beforeStart () override
 
bool threadInit () override
 
void run () override
 
void afterStart (bool success) override
 
void onStop () override
 
void threadRelease () override
 
bool init_facilities (const bool use_direct_kin) override
 Initialize support modules and connections to perform a visual servoing task. More...
 
bool reset_facilities () override
 Reset support modules and connections to perform the current initialized visual servoing task. More...
 
bool stop_facilities () override
 Stop and disconnect support modules and connections used for visual servoing. More...
 
bool go_to_px_goal (const std::vector< std::vector< double >> &vec_px_l, const std::vector< std::vector< double >> &vec_px_r) override
 
bool go_to_pose_goal (const std::vector< double > &vec_x, const std::vector< double > &vec_o) override
 Set the goal point (3D for the position + 4D axis-angle for the orientation) and start visual servoing. More...
 
bool set_modality (const std::string &mode) override
 Set visual servoing operating mode between: More...
 
bool set_visual_servo_control (const std::string &control) override
 Set visual servo control law between: More...
 
bool set_control_point (const std::string &point) override
 Set the point controlled during visual servoing. More...
 
std::vector< std::string > get_visual_servoing_info () override
 Return useful information for visual servoing. More...
 
bool set_go_to_goal_tolerance (const double tol) override
 Set visual servoing goal tolerance. More...
 
bool check_visual_servoing_controller () override
 Check once whether the visual servoing controller is running or not. More...
 
bool wait_visual_servoing_done (const double period, const double timeout) override
 Wait until visual servoing reaches the goal. More...
 
bool stop_controller () override
 Ask for an immediate stop of the visual servoing controller. More...
 
bool set_translation_gain (const double K_x_1, const double K_x_2) override
 Set the translation gains of the visual servoing control algorithm. More...
 
bool set_max_translation_velocity (const double max_x_dot) override
 Set the maximum translation velocity of the visual servoing control algorithm (same for each axis). More...
 
bool set_translation_gain_switch_tolerance (const double K_x_tol) override
 Set the tolerance, in pixels, at which the translation control law swithces its gain value. More...
 
bool set_orientation_gain (const double K_o_1, const double K_o_2) override
 Set the orientation gains of the visual servoing control algorithm. More...
 
bool set_max_orientation_velocity (const double max_o_dot) override
 Set the maximum angular velocity of the axis-angle velocity vector of the visual servoing control algorithm. More...
 
bool set_orientation_gain_switch_tolerance (const double K_o_tol) override
 Set the tolerance, in pixels, at which the orientation control law swithces its gain value. More...
 
std::vector< std::vector< double > > get_3D_goal_positions_from_3D_pose (const std::vector< double > &x, const std::vector< double > &o) override
 Helper function: extract four Cartesian points lying on the plane defined by the frame o in the position x relative to the robot base frame. More...
 
std::vector< std::vector< double > > get_goal_pixels_from_3D_pose (const std::vector< double > &x, const std::vector< double > &o, const std::string &cam) override
 Helper function: extract four 2D pixel points lying on the plane defined by the frame o in the position x relative to the robot base frame. More...
 
bool quit () override
 Gently close the visual servoing device, deallocating resources. More...
 
bool stored_init (const std::string &label) override
 Initialize the robot to an initial position. More...
 
bool stored_go_to_goal (const std::string &label) override
 Set the robot visual servoing goal. More...
 
bool get_goal_from_sfm () override
 Get goal point from SFM module. More...
 

Private Member Functions

void decoupledImageBasedVisualServoControl ()
 
void robustImageBasedVisualServoControl ()
 
void cartesianPositionBasedVisualServoControl ()
 
bool setRightArmCartesianController ()
 
bool setGazeController ()
 
bool setCommandPort ()
 
bool setTorsoDOF ()
 
bool unsetTorsoDOF ()
 
std::vector< yarp::sig::Vector > getPixelsFromPose (const yarp::sig::Vector &pose, const CamSel &cam)
 
std::vector< yarp::sig::Vector > getControlPixelsFromPose (const yarp::sig::Vector &pose, const CamSel &cam, const PixelControlMode &mode)
 
std::vector< yarp::sig::Vector > getControlPointsFromPose (const yarp::sig::Vector &pose)
 
yarp::sig::Vector getPixelFromPoint (const CamSel &cam, const yarp::sig::Vector &p) const
 
yarp::sig::Vector getControlPixelFromPoint (const CamSel &cam, const yarp::sig::Vector &p) const
 
void getCurrentStereoFeaturesAndJacobian (const std::vector< yarp::sig::Vector > &left_px, const std::vector< yarp::sig::Vector > &right_px, yarp::sig::Vector &features, yarp::sig::Matrix &jacobian)
 
yarp::sig::Vector getJacobianU (const CamSel &cam, const yarp::sig::Vector &px)
 
yarp::sig::Vector getJacobianV (const CamSel &cam, const yarp::sig::Vector &px)
 
bool setCameraTransformations ()
 
bool setPoseGoal (const yarp::sig::Vector &goal_x, const yarp::sig::Vector &goal_o)
 
bool setPixelGoal (const std::vector< yarp::sig::Vector > &l_px_goal, const std::vector< yarp::sig::Vector > &r_px_goal)
 
void backproc_UpdateVisualServoingParamters ()
 
yarp::sig::Vector averagePose (const yarp::sig::Vector &l_pose, const yarp::sig::Vector &r_pose) const
 
bool checkVisualServoingStatus (const yarp::sig::Vector &px_cur, const double tol)
 
bool checkVisualServoingStatus (const yarp::sig::Vector &pose_cur, const double tol_position, const double tol_orientation, const double tol_angle)
 
void yInfoVerbose (const yarp::os::ConstString &str) const
 
void yWarningVerbose (const yarp::os::ConstString &str) const
 
void yErrorVerbose (const yarp::os::ConstString &str) const
 
yarp::sig::Vector stdVectorOfVectorsToVector (const std::vector< yarp::sig::Vector > &vectors)
 

Private Attributes

bool verbosity_ = false
 
bool sim_ = false
 
yarp::os::ConstString robot_name_ = "icub"
 
VisualServoControl vs_control_ = VisualServoControl::decoupled
 
OperatingMode op_mode_ = OperatingMode::pose
 
yarp::dev::PolyDriver rightarm_cartesian_driver_
 
yarp::dev::ICartesianControl * itf_rightarm_cart_
 
yarp::dev::PolyDriver gaze_driver_
 
yarp::dev::IGazeControl * itf_gaze_
 
bool vs_control_running_ = false
 
bool vs_goal_reached_ = false
 
const double Ts_ = 0.1
 
std::array< double, 2 > K_x_ = {{0.5, 0.25}}
 
std::array< double, 2 > K_o_ = {{3.5, 0.5}}
 
double max_x_dot_ = 0.035
 
double max_o_dot_ = 10.0 * M_PI / 180.0
 
double K_x_tol_ = 10.0
 
double K_o_tol_ = 10.0
 
double K_position_tol_ = 0.03
 
double K_orientation_tol_ = 9.0 * M_PI / 180.0
 
double K_angle_tol_ = 3.0 * M_PI / 180.0
 
bool K_x_hysteresis_ = false
 
bool K_o_hysteresis_ = false
 
bool K_pose_hysteresis_ = false
 
double tol_px_ = 1.0
 
double tol_position_ = 0.01
 
double tol_orientation_ = 3.0 * M_PI / 180.0
 
double tol_angle_ = 1.0 * M_PI / 180.0
 
double traj_time_ = 1.0
 
yarp::sig::Matrix l_proj_
 
yarp::sig::Matrix r_proj_
 
yarp::sig::Vector goal_pose_ = yarp::math::zeros(7)
 
yarp::sig::Vector px_des_ = yarp::math::zeros(16)
 
yarp::sig::Matrix l_H_eye_to_r_ = yarp::math::zeros(4, 4)
 
yarp::sig::Matrix r_H_eye_to_r_ = yarp::math::zeros(4, 4)
 
yarp::sig::Matrix l_H_r_to_cam_ = yarp::math::zeros(4, 4)
 
yarp::sig::Matrix r_H_r_to_cam_ = yarp::math::zeros(4, 4)
 
std::mutex mtx_px_des_
 
std::mutex mtx_H_eye_cam_
 
std::thread * thr_background_update_params_
 
std::vector< yarp::sig::Vector > l_px_goal_ = std::vector<yarp::sig::Vector>(4)
 
std::vector< yarp::sig::Vector > r_px_goal_ = std::vector<yarp::sig::Vector>(4)
 
int ctx_local_cart_
 
int ctx_remote_cart_
 
yarp::os::BufferedPort< yarp::sig::Vector > port_pose_left_in_
 
yarp::os::BufferedPort< yarp::sig::Vector > port_pose_right_in_
 
yarp::os::BufferedPort< yarp::sig::ImageOf< yarp::sig::PixelRgb > > port_image_left_in_
 
yarp::os::BufferedPort< yarp::sig::ImageOf< yarp::sig::PixelRgb > > port_image_left_out_
 
yarp::os::BufferedPort< yarp::os::Bottle > port_click_left_
 
yarp::os::BufferedPort< yarp::sig::ImageOf< yarp::sig::PixelRgb > > port_image_right_in_
 
yarp::os::BufferedPort< yarp::sig::ImageOf< yarp::sig::PixelRgb > > port_image_right_out_
 
yarp::os::BufferedPort< yarp::os::Bottle > port_click_right_
 
yarp::os::Port port_rpc_command_
 
yarp::os::RpcClient port_rpc_tracker_left_
 
yarp::os::RpcClient port_rpc_tracker_right_
 
bool is_stopping_backproc_update_vs_params = true
 
yarp::os::BufferedPort< yarp::sig::Vector > port_pose_px_l_
 
yarp::os::BufferedPort< yarp::sig::Vector > port_pose_px_r_
 
yarp::os::BufferedPort< yarp::sig::Vector > port_kin_px_l_
 
yarp::os::BufferedPort< yarp::sig::Vector > port_kin_px_r_
 
yarp::os::BufferedPort< yarp::sig::Vector > port_goal_px_l_
 
yarp::os::BufferedPort< yarp::sig::Vector > port_goal_px_r_
 
yarp::os::BufferedPort< yarp::sig::Vector > port_pose_avg_
 
yarp::os::BufferedPort< yarp::sig::Vector > port_pose_kin_
 
yarp::os::BufferedPort< yarp::sig::Vector > port_pose_goal_
 

Detailed Description

Definition at line 32 of file VisualServoingServer.h.

Member Enumeration Documentation

◆ OperatingMode

Enumerator
position 
orientation 
pose 

Definition at line 174 of file VisualServoingServer.h.

◆ PixelControlMode

Enumerator
all 

Definition at line 172 of file VisualServoingServer.h.

◆ VisualServoControl

Enumerator
decoupled 
robust 
cartesian 

Definition at line 170 of file VisualServoingServer.h.

Constructor & Destructor Documentation

◆ VisualServoingServer()

VisualServoingServer::VisualServoingServer ( )

Definition at line 20 of file VisualServoingServer.cpp.

◆ ~VisualServoingServer()

VisualServoingServer::~VisualServoingServer ( )

Definition at line 27 of file VisualServoingServer.cpp.

Member Function Documentation

◆ afterStart()

void VisualServoingServer::afterStart ( bool  success)
overrideprotected

Definition at line 1032 of file VisualServoingServer.cpp.

◆ averagePose()

Vector VisualServoingServer::averagePose ( const yarp::sig::Vector &  l_pose,
const yarp::sig::Vector &  r_pose 
) const
private

Definition at line 2818 of file VisualServoingServer.cpp.

References checkVisualServoingStatus().

Here is the call graph for this function:

◆ backproc_UpdateVisualServoingParamters()

void VisualServoingServer::backproc_UpdateVisualServoingParamters ( )
private

Definition at line 2796 of file VisualServoingServer.cpp.

Referenced by threadInit().

◆ beforeStart()

void VisualServoingServer::beforeStart ( )
overrideprotected

Definition at line 986 of file VisualServoingServer.cpp.

◆ cartesianPositionBasedVisualServoControl()

void VisualServoingServer::cartesianPositionBasedVisualServoControl ( )
private

Definition at line 2071 of file VisualServoingServer.cpp.

◆ check_visual_servoing_controller()

bool VisualServoingServer::check_visual_servoing_controller ( )
overrideprotectedvirtual

Check once whether the visual servoing controller is running or not.

Returns
true/false on it is running/not running.
Note
The visual servoing controller may be terminated due to many different reasons, not strictly related to reaching the goal.

Reimplemented from VisualServoingIDL.

Definition at line 1220 of file VisualServoingServer.cpp.

◆ checkVisualServoingController()

bool VisualServoingServer::checkVisualServoingController ( )
override

Definition at line 589 of file VisualServoingServer.cpp.

◆ checkVisualServoingStatus() [1/2]

bool VisualServoingServer::checkVisualServoingStatus ( const yarp::sig::Vector &  px_cur,
const double  tol 
)
private

Referenced by averagePose().

◆ checkVisualServoingStatus() [2/2]

bool VisualServoingServer::checkVisualServoingStatus ( const yarp::sig::Vector &  pose_cur,
const double  tol_position,
const double  tol_orientation,
const double  tol_angle 
)
private

◆ close()

bool VisualServoingServer::close ( )
override

Definition at line 185 of file VisualServoingServer.cpp.

◆ decoupledImageBasedVisualServoControl()

void VisualServoingServer::decoupledImageBasedVisualServoControl ( )
private

Definition at line 1315 of file VisualServoingServer.cpp.

◆ get3DGoalPositionsFrom3DPose()

std::vector< Vector > VisualServoingServer::get3DGoalPositionsFrom3DPose ( const yarp::sig::Vector &  x,
const yarp::sig::Vector &  o 
)
override

Definition at line 675 of file VisualServoingServer.cpp.

◆ get_3D_goal_positions_from_3D_pose()

std::vector< std::vector< double > > VisualServoingServer::get_3D_goal_positions_from_3D_pose ( const std::vector< double > &  x,
const std::vector< double > &  o 
)
overrideprotectedvirtual

Helper function: extract four Cartesian points lying on the plane defined by the frame o in the position x relative to the robot base frame.

Parameters
xa 3D vector which is filled with the actual position (x, y, z) [m].
oa 4D vector which is filled with the actual orientation using axis-angle representation (xa, ya, za) and (theta) [rad].
Returns
on success: a collection of four Cartesian points (position only) extracted from the plane defined by x and o; on failure: an empty list.
Note
It is always suggested to check whether the returned list is empty or not and to take proper counter actions.

Reimplemented from VisualServoingIDL.

Definition at line 1274 of file VisualServoingServer.cpp.

◆ get_goal_from_sfm()

bool VisualServoingServer::get_goal_from_sfm ( )
overrideprotectedvirtual

Get goal point from SFM module.

The point is taken by clicking on a dedicated 'yarpview' GUI and the orientation is hard-coded.

Note
This service is experimental and should be used with care.
Returns
true upon success, false otherwise.

Reimplemented from VisualServoingIDL.

Definition at line 1099 of file VisualServoingServer.cpp.

◆ get_goal_pixels_from_3D_pose()

std::vector< std::vector< double > > VisualServoingServer::get_goal_pixels_from_3D_pose ( const std::vector< double > &  x,
const std::vector< double > &  o,
const std::string &  cam 
)
overrideprotectedvirtual

Helper function: extract four 2D pixel points lying on the plane defined by the frame o in the position x relative to the robot base frame.

Parameters
xa 3D vector which is filled with the actual position (x, y, z) [m].
oa 4D vector which is filled with the actual orientation using axis-angle representation (xa, ya, za) and (theta) [m]/[rad].
cameither "left" or "right" to select left or right camera.
Returns
on success: a collection of three (u, v) pixel points extracted from the plane defined by x and o; on failure: an empty list.
Note
It is always suggested to check whether the returned list is empty or not and to take proper counter actions.

Reimplemented from VisualServoingIDL.

Definition at line 1292 of file VisualServoingServer.cpp.

◆ get_visual_servoing_info()

std::vector< std::string > VisualServoingServer::get_visual_servoing_info ( )
overrideprotectedvirtual

Return useful information for visual servoing.

Returns
All the visual servoing information.

Reimplemented from VisualServoingIDL.

Definition at line 1202 of file VisualServoingServer.cpp.

◆ getControlPixelFromPoint()

Vector VisualServoingServer::getControlPixelFromPoint ( const CamSel &  cam,
const yarp::sig::Vector &  p 
) const
private

Definition at line 2626 of file VisualServoingServer.cpp.

◆ getControlPixelsFromPose()

std::vector< Vector > VisualServoingServer::getControlPixelsFromPose ( const yarp::sig::Vector &  pose,
const CamSel &  cam,
const PixelControlMode mode 
)
private

Definition at line 2553 of file VisualServoingServer.cpp.

◆ getControlPointsFromPose()

std::vector< Vector > VisualServoingServer::getControlPointsFromPose ( const yarp::sig::Vector &  pose)
private

Definition at line 2576 of file VisualServoingServer.cpp.

◆ getCurrentStereoFeaturesAndJacobian()

void VisualServoingServer::getCurrentStereoFeaturesAndJacobian ( const std::vector< yarp::sig::Vector > &  left_px,
const std::vector< yarp::sig::Vector > &  right_px,
yarp::sig::Vector &  features,
yarp::sig::Matrix &  jacobian 
)
private

Definition at line 2646 of file VisualServoingServer.cpp.

◆ getGoalPixelsFrom3DPose()

std::vector< Vector > VisualServoingServer::getGoalPixelsFrom3DPose ( const yarp::sig::Vector &  x,
const yarp::sig::Vector &  o,
const CamSel &  cam 
)
override

Definition at line 695 of file VisualServoingServer.cpp.

◆ getJacobianU()

Vector VisualServoingServer::getJacobianU ( const CamSel &  cam,
const yarp::sig::Vector &  px 
)
private

Definition at line 2685 of file VisualServoingServer.cpp.

◆ getJacobianV()

Vector VisualServoingServer::getJacobianV ( const CamSel &  cam,
const yarp::sig::Vector &  px 
)
private

Definition at line 2710 of file VisualServoingServer.cpp.

◆ getPixelFromPoint()

Vector VisualServoingServer::getPixelFromPoint ( const CamSel &  cam,
const yarp::sig::Vector &  p 
) const
private

Definition at line 2620 of file VisualServoingServer.cpp.

◆ getPixelsFromPose()

std::vector< Vector > VisualServoingServer::getPixelsFromPose ( const yarp::sig::Vector &  pose,
const CamSel &  cam 
)
private

Definition at line 2537 of file VisualServoingServer.cpp.

◆ getVisualServoingInfo()

bool VisualServoingServer::getVisualServoingInfo ( yarp::os::Bottle &  info)
override

Definition at line 573 of file VisualServoingServer.cpp.

◆ go_to_pose_goal()

bool VisualServoingServer::go_to_pose_goal ( const std::vector< double > &  vec_x,
const std::vector< double > &  vec_o 
)
overrideprotectedvirtual

Set the goal point (3D for the position + 4D axis-angle for the orientation) and start visual servoing.

Parameters
vec_xa 3D vector which contains the (x, y, z) Cartesian coordinates of the goal.
vec_oa 4D vector which contains the (x, y, z) axis and theta angle of rotation of the goal.
Note
By invoking this method, the visual servoing goal will be reached in position and orientation together with two parallel tasks.
Returns
true/false on success/failure.

Reimplemented from VisualServoingIDL.

Definition at line 1172 of file VisualServoingServer.cpp.

◆ go_to_px_goal() [1/2]

virtual bool VisualServoingIDL::go_to_px_goal ( const std::vector< std::vector< double > > &  vec_px_l,
const std::vector< std::vector< double > > &  vec_px_r 
)
virtualinherited

Set the goal points on both left and right camera image plane and start visual servoing.

Parameters
vec_px_la collection of four 2D vectors which contains the (u, v) coordinates of the pixels within the left image plane.
vec_px_ra collection of four 2D vectors which contains the (u, v) coordinates of the pixels within the right image plane.
Note
By invoking this method, the visual servoing goal will be reached in orientation first, then in position. This is because there may not be a feasible position solution for every possible orientation.
Returns
true/false on success/failure.

◆ go_to_px_goal() [2/2]

bool VisualServoingServer::go_to_px_goal ( const std::vector< std::vector< double >> &  vec_px_l,
const std::vector< std::vector< double >> &  vec_px_r 
)
overrideprotected

Definition at line 1145 of file VisualServoingServer.cpp.

◆ goToGoal() [1/2]

bool VisualServoingServer::goToGoal ( const yarp::sig::Vector &  vec_x,
const yarp::sig::Vector &  vec_o 
)
override

Referenced by stopFacilities().

◆ goToGoal() [2/2]

bool VisualServoingServer::goToGoal ( const std::vector< yarp::sig::Vector > &  vec_px_l,
const std::vector< yarp::sig::Vector > &  vec_px_r 
)
override

◆ goToSFMGoal()

bool VisualServoingServer::goToSFMGoal ( )
override

Definition at line 925 of file VisualServoingServer.cpp.

◆ help()

virtual std::vector<std::string> VisualServoingIDL::help ( const std::string &  functionName = "--all")
virtualinherited

◆ init_facilities()

bool VisualServoingServer::init_facilities ( const bool  use_direct_kin)
overrideprotectedvirtual

Initialize support modules and connections to perform a visual servoing task.

This method must be called before any other visual servoing methods. Returns upon successful or failure setup.

Parameters
use_direct_kininstruct the visual servoing control to either use direct kinematic or an estimated/refined pose of the end-effector.
Note
Default value: false. There usually is an error in the robot direct kinematics that should be compensated to perform precise visual servoing. To this end, a recursive Bayesian estimation filter is used to compensate for this error. Such filter is initialized during initialization execution.
Returns
true/false on success/failure.

Reimplemented from VisualServoingIDL.

Definition at line 1127 of file VisualServoingServer.cpp.

◆ initFacilities()

bool VisualServoingServer::initFacilities ( const bool  use_direct_kin)
override

Definition at line 253 of file VisualServoingServer.cpp.

◆ onStop()

void VisualServoingServer::onStop ( )
overrideprotected

Definition at line 1051 of file VisualServoingServer.cpp.

◆ open()

bool VisualServoingServer::open ( yarp::os::Searchable &  config)
override

Definition at line 35 of file VisualServoingServer.cpp.

◆ quit()

bool VisualServoingServer::quit ( )
overrideprotectedvirtual

Gently close the visual servoing device, deallocating resources.

Reimplemented from VisualServoingIDL.

Definition at line 1105 of file VisualServoingServer.cpp.

◆ read()

virtual bool VisualServoingIDL::read ( yarp::os::ConnectionReader &  connection)
overridevirtualinherited

◆ reset_facilities()

bool VisualServoingServer::reset_facilities ( )
overrideprotectedvirtual

Reset support modules and connections to perform the current initialized visual servoing task.

Returns upon successful or failure setup.

Note
This method also resets the recursive Bayesian estimation filter. It may happen that the recursive Bayesian filter does not provide satisfactory pose estimation or diverges. Thus this method can be used to reset the filter.
Returns
true/false on success/failure.

Reimplemented from VisualServoingIDL.

Definition at line 1133 of file VisualServoingServer.cpp.

◆ resetFacilities()

bool VisualServoingServer::resetFacilities ( )
override

Definition at line 367 of file VisualServoingServer.cpp.

◆ robustImageBasedVisualServoControl()

void VisualServoingServer::robustImageBasedVisualServoControl ( )
private

Definition at line 1716 of file VisualServoingServer.cpp.

◆ run()

void VisualServoingServer::run ( )
overrideprotected

Definition at line 1021 of file VisualServoingServer.cpp.

◆ set_control_point()

bool VisualServoingServer::set_control_point ( const std::string &  point)
overrideprotectedvirtual

Set the point controlled during visual servoing.

Parameters
pointlabel of the point to control.
Returns
true/false on success/failure.
Note
The points available to control are identified by a distinct, unique label. Such labels can are stored in the bottle returned by the getInfo() method.

Reimplemented from VisualServoingIDL.

Definition at line 1196 of file VisualServoingServer.cpp.

◆ set_go_to_goal_tolerance()

bool VisualServoingServer::set_go_to_goal_tolerance ( const double  tol)
overrideprotectedvirtual

Set visual servoing goal tolerance.

Parameters
tolthe tolerance in pixel.
Returns
true/false on success/failure.
Note
Default value: 15.0 [pixel].

Reimplemented from VisualServoingIDL.

Definition at line 1214 of file VisualServoingServer.cpp.

◆ set_max_orientation_velocity()

bool VisualServoingServer::set_max_orientation_velocity ( const double  max_o_dot)
overrideprotectedvirtual

Set the maximum angular velocity of the axis-angle velocity vector of the visual servoing control algorithm.

Parameters
max_x_dotthe maximum allowed angular velocity [rad/s].
Returns
true/false on success/failure.
Note
Default value: 5 * (PI / 180.0) [rad/s].

Reimplemented from VisualServoingIDL.

Definition at line 1262 of file VisualServoingServer.cpp.

◆ set_max_translation_velocity()

bool VisualServoingServer::set_max_translation_velocity ( const double  max_x_dot)
overrideprotectedvirtual

Set the maximum translation velocity of the visual servoing control algorithm (same for each axis).

Parameters
max_x_dotthe maximum allowed velocity for x, y, z coordinates [m/s].
Returns
true/false on success/failure.
Note
Default value: max_x_dot = 0.025 [m/s].

Reimplemented from VisualServoingIDL.

Definition at line 1244 of file VisualServoingServer.cpp.

◆ set_modality()

bool VisualServoingServer::set_modality ( const std::string &  mode)
overrideprotectedvirtual

Set visual servoing operating mode between:

  1. 'position': position-only visual servo control;
  2. 'orientation': orientation-only visual servo control;
  3. 'pose': position + orientation visual servo control.
    Parameters
    modea label referring to one of the three operating mode, i.e. 'position', 'orientation' or 'pose'.
    Returns
    true/false on success/failure.

Reimplemented from VisualServoingIDL.

Definition at line 1184 of file VisualServoingServer.cpp.

◆ set_orientation_gain()

bool VisualServoingServer::set_orientation_gain ( const double  K_o_1,
const double  K_o_2 
)
overrideprotectedvirtual

Set the orientation gains of the visual servoing control algorithm.

The two values are used, respectively, when the end-effector is far away from and close to the goal.

Returns
true/false on success/failure.
Note
Warning: higher values of the gain corresponds to higher orientation velocities and oscillation about the goal.
Default values: K_o_1 = 1.5, K_o_2 = 0.375.

Reimplemented from VisualServoingIDL.

Definition at line 1256 of file VisualServoingServer.cpp.

◆ set_orientation_gain_switch_tolerance()

bool VisualServoingServer::set_orientation_gain_switch_tolerance ( const double  K_o_tol)
overrideprotectedvirtual

Set the tolerance, in pixels, at which the orientation control law swithces its gain value.

Returns
true/false on success/failure.
Note
Default value: K_o_tol = 30.0 [pixel].

Reimplemented from VisualServoingIDL.

Definition at line 1268 of file VisualServoingServer.cpp.

◆ set_translation_gain()

bool VisualServoingServer::set_translation_gain ( const double  K_x_1,
const double  K_x_2 
)
overrideprotectedvirtual

Set the translation gains of the visual servoing control algorithm.

The two values are used, respectively, when the end-effector is far away from and close to the goal.

Returns
true/false on success/failure.
Note
Warning: higher values of the gain corresponds to higher translation velocities and oscillation about the goal.
Default values: K_x_1 = 1.0, K_x_2 = 0.25.

Reimplemented from VisualServoingIDL.

Definition at line 1238 of file VisualServoingServer.cpp.

◆ set_translation_gain_switch_tolerance()

bool VisualServoingServer::set_translation_gain_switch_tolerance ( const double  K_x_tol)
overrideprotectedvirtual

Set the tolerance, in pixels, at which the translation control law swithces its gain value.

Returns
true/false on success/failure.
Note
Default value: K_x_tol = 30.0 [pixel].

Reimplemented from VisualServoingIDL.

Definition at line 1250 of file VisualServoingServer.cpp.

◆ set_visual_servo_control()

bool VisualServoingServer::set_visual_servo_control ( const std::string &  control)
overrideprotectedvirtual

Set visual servo control law between:

  1. 'decoupled': image-based visual servoing with decoupled position and orientation control law, the control law was proposed in [1];
  2. 'robust': image-based visual servoing with averaged image Jacobians, the control law was proposed in [2];
    Parameters
    modea label referring to one of the three visual servo controls, i.e. 'position', 'orientation' or 'pose'.
    Note
    [1] C. Fantacci, G. Vezzani, U. Pattacini, V. Tikhanoff and L. Natale, "Precise markerless visual servoing on unknown objects for humanoid robot platforms", to appear. [2] E. Malis, “Improving vision-based control using efficient second-order minimization techniques”, IEEE ICRA, vol. 2, p. 1843–1848, 2004.
    Returns
    true/false on success/failure.

Reimplemented from VisualServoingIDL.

Definition at line 1190 of file VisualServoingServer.cpp.

◆ setCameraTransformations()

bool VisualServoingServer::setCameraTransformations ( )
private

Definition at line 2735 of file VisualServoingServer.cpp.

◆ setCommandPort()

bool VisualServoingServer::setCommandPort ( )
private

Definition at line 2457 of file VisualServoingServer.cpp.

◆ setControlPoint()

bool VisualServoingServer::setControlPoint ( const yarp::os::ConstString &  point)
override

Definition at line 565 of file VisualServoingServer.cpp.

◆ setGazeController()

bool VisualServoingServer::setGazeController ( )
private

Definition at line 2430 of file VisualServoingServer.cpp.

◆ setGoToGoalTolerance()

bool VisualServoingServer::setGoToGoalTolerance ( const double  tol = 15.0)
override

Definition at line 581 of file VisualServoingServer.cpp.

◆ setMaxOrientationVelocity()

bool VisualServoingServer::setMaxOrientationVelocity ( const double  max_o_dot)
override

Definition at line 659 of file VisualServoingServer.cpp.

◆ setMaxTranslationVelocity()

bool VisualServoingServer::setMaxTranslationVelocity ( const double  max_x_dot)
override

Definition at line 634 of file VisualServoingServer.cpp.

◆ setModality()

bool VisualServoingServer::setModality ( const std::string &  mode)
override

Definition at line 535 of file VisualServoingServer.cpp.

◆ setOrientationGain()

bool VisualServoingServer::setOrientationGain ( const double  K_x_1 = 1.5,
const double  K_x_2 = 0.375 
)
override

Definition at line 650 of file VisualServoingServer.cpp.

◆ setOrientationGainSwitchTolerance()

bool VisualServoingServer::setOrientationGainSwitchTolerance ( const double  K_o_tol = 30.0)
override

Definition at line 667 of file VisualServoingServer.cpp.

◆ setPixelGoal()

bool VisualServoingServer::setPixelGoal ( const std::vector< yarp::sig::Vector > &  l_px_goal,
const std::vector< yarp::sig::Vector > &  r_px_goal 
)
private

Definition at line 2776 of file VisualServoingServer.cpp.

◆ setPoseGoal()

bool VisualServoingServer::setPoseGoal ( const yarp::sig::Vector &  goal_x,
const yarp::sig::Vector &  goal_o 
)
private

Definition at line 2767 of file VisualServoingServer.cpp.

◆ setRightArmCartesianController()

bool VisualServoingServer::setRightArmCartesianController ( )
private

Definition at line 2353 of file VisualServoingServer.cpp.

◆ setTorsoDOF()

bool VisualServoingServer::setTorsoDOF ( )
private

Definition at line 2491 of file VisualServoingServer.cpp.

◆ setTranslationGain()

bool VisualServoingServer::setTranslationGain ( const double  K_x_1 = 1.0,
const double  K_x_2 = 0.25 
)
override

Definition at line 625 of file VisualServoingServer.cpp.

◆ setTranslationGainSwitchTolerance()

bool VisualServoingServer::setTranslationGainSwitchTolerance ( const double  K_x_tol = 30.0)
override

Definition at line 642 of file VisualServoingServer.cpp.

◆ setVisualServoControl()

bool VisualServoingServer::setVisualServoControl ( const std::string &  control)
override

Definition at line 550 of file VisualServoingServer.cpp.

◆ stdVectorOfVectorsToVector()

Vector VisualServoingServer::stdVectorOfVectorsToVector ( const std::vector< yarp::sig::Vector > &  vectors)
private

Definition at line 2863 of file VisualServoingServer.cpp.

Referenced by yErrorVerbose().

◆ stop_controller()

bool VisualServoingServer::stop_controller ( )
overrideprotectedvirtual

Ask for an immediate stop of the visual servoing controller.

[wait for reply]

Returns
true/false on success/failure.

Reimplemented from VisualServoingIDL.

Definition at line 1232 of file VisualServoingServer.cpp.

◆ stop_facilities()

bool VisualServoingServer::stop_facilities ( )
overrideprotectedvirtual

Stop and disconnect support modules and connections used for visual servoing.

This method must be called when visual servoing is no longer needed or a new visual servoing task need to be initialized.

Note
This method also stops the recursive Bayesian estimation filter. Thus it is suggested to call this method every time visual servoing has been completed/interrupted to have the filter stopped and initialized again during the next init call.
Returns
true/false on success/failure.

Reimplemented from VisualServoingIDL.

Definition at line 1139 of file VisualServoingServer.cpp.

◆ stopController()

bool VisualServoingServer::stopController ( )
override

Definition at line 613 of file VisualServoingServer.cpp.

◆ stopFacilities()

bool VisualServoingServer::stopFacilities ( )
override

Definition at line 402 of file VisualServoingServer.cpp.

References goToGoal().

Here is the call graph for this function:

◆ stored_go_to_goal()

bool VisualServoingServer::stored_go_to_goal ( const std::string &  label)
overrideprotectedvirtual

Set the robot visual servoing goal.

The goals are stored on an external file and are referenced by a unique label.

Parameters
labela label referring to one of the available goals; the string shall be one of the available modes returned by the get_info() method.
Returns
true upon success, false otherwise.

Reimplemented from VisualServoingIDL.

Definition at line 1093 of file VisualServoingServer.cpp.

◆ stored_init()

bool VisualServoingServer::stored_init ( const std::string &  label)
overrideprotectedvirtual

Initialize the robot to an initial position.

The initial positions are stored on an external file and are referenced by a unique label.

Parameters
labela label referring to one of the available initial positions; the string shall be one of the available modes returned by the get_info() method.
Returns
true upon success, false otherwise.

Reimplemented from VisualServoingIDL.

Definition at line 1087 of file VisualServoingServer.cpp.

◆ storedGoToGoal()

bool VisualServoingServer::storedGoToGoal ( const std::string &  label)
override

Definition at line 846 of file VisualServoingServer.cpp.

◆ storedInit()

bool VisualServoingServer::storedInit ( const std::string &  label)
override

Definition at line 718 of file VisualServoingServer.cpp.

◆ threadInit()

bool VisualServoingServer::threadInit ( )
overrideprotected

Definition at line 992 of file VisualServoingServer.cpp.

References backproc_UpdateVisualServoingParamters().

Here is the call graph for this function:

◆ threadRelease()

void VisualServoingServer::threadRelease ( )
overrideprotected

Definition at line 1057 of file VisualServoingServer.cpp.

◆ unsetTorsoDOF()

bool VisualServoingServer::unsetTorsoDOF ( )
private

Definition at line 2514 of file VisualServoingServer.cpp.

◆ wait_visual_servoing_done()

bool VisualServoingServer::wait_visual_servoing_done ( const double  period,
const double  timeout 
)
overrideprotectedvirtual

Wait until visual servoing reaches the goal.

[wait for reply]

Parameters
periodthe check time period [s].
timeoutthe check expiration time [s]. If timeout <= 0 (as by default) the check will be performed without time limitation.
Returns
true for success, false for failure and timeout expired.
Note
The tolerance to which the goal is considered achieved can be set with the method setGoToGoalTolerance().
Default values: period 0.1 [s], timeout 0.0 [s].

Reimplemented from VisualServoingIDL.

Definition at line 1226 of file VisualServoingServer.cpp.

◆ waitVisualServoingDone()

bool VisualServoingServer::waitVisualServoingDone ( const double  period = 0.1,
const double  timeout = 0.0 
)
override

Definition at line 601 of file VisualServoingServer.cpp.

◆ yErrorVerbose()

void VisualServoingServer::yErrorVerbose ( const yarp::os::ConstString &  str) const
inlineprivate

Definition at line 300 of file VisualServoingServer.h.

References stdVectorOfVectorsToVector().

Here is the call graph for this function:

◆ yInfoVerbose()

void VisualServoingServer::yInfoVerbose ( const yarp::os::ConstString &  str) const
inlineprivate

Definition at line 298 of file VisualServoingServer.h.

◆ yWarningVerbose()

void VisualServoingServer::yWarningVerbose ( const yarp::os::ConstString &  str) const
inlineprivate

Definition at line 299 of file VisualServoingServer.h.

Member Data Documentation

◆ ctx_local_cart_

int VisualServoingServer::ctx_local_cart_
private

Definition at line 229 of file VisualServoingServer.h.

◆ ctx_remote_cart_

int VisualServoingServer::ctx_remote_cart_
private

Definition at line 230 of file VisualServoingServer.h.

◆ gaze_driver_

yarp::dev::PolyDriver VisualServoingServer::gaze_driver_
private

Definition at line 187 of file VisualServoingServer.h.

◆ goal_pose_

yarp::sig::Vector VisualServoingServer::goal_pose_ = yarp::math::zeros(7)
private

Definition at line 214 of file VisualServoingServer.h.

◆ is_stopping_backproc_update_vs_params

bool VisualServoingServer::is_stopping_backproc_update_vs_params = true
private

Definition at line 288 of file VisualServoingServer.h.

◆ itf_gaze_

yarp::dev::IGazeControl* VisualServoingServer::itf_gaze_
private

Definition at line 188 of file VisualServoingServer.h.

◆ itf_rightarm_cart_

yarp::dev::ICartesianControl* VisualServoingServer::itf_rightarm_cart_
private

Definition at line 185 of file VisualServoingServer.h.

◆ K_angle_tol_

double VisualServoingServer::K_angle_tol_ = 3.0 * M_PI / 180.0
private

Definition at line 201 of file VisualServoingServer.h.

◆ K_o_

std::array<double, 2> VisualServoingServer::K_o_ = {{3.5, 0.5}}
private

Definition at line 194 of file VisualServoingServer.h.

◆ K_o_hysteresis_

bool VisualServoingServer::K_o_hysteresis_ = false
private

Definition at line 203 of file VisualServoingServer.h.

◆ K_o_tol_

double VisualServoingServer::K_o_tol_ = 10.0
private

Definition at line 198 of file VisualServoingServer.h.

◆ K_orientation_tol_

double VisualServoingServer::K_orientation_tol_ = 9.0 * M_PI / 180.0
private

Definition at line 200 of file VisualServoingServer.h.

◆ K_pose_hysteresis_

bool VisualServoingServer::K_pose_hysteresis_ = false
private

Definition at line 204 of file VisualServoingServer.h.

◆ K_position_tol_

double VisualServoingServer::K_position_tol_ = 0.03
private

Definition at line 199 of file VisualServoingServer.h.

◆ K_x_

std::array<double, 2> VisualServoingServer::K_x_ = {{0.5, 0.25}}
private

Definition at line 193 of file VisualServoingServer.h.

◆ K_x_hysteresis_

bool VisualServoingServer::K_x_hysteresis_ = false
private

Definition at line 202 of file VisualServoingServer.h.

◆ K_x_tol_

double VisualServoingServer::K_x_tol_ = 10.0
private

Definition at line 197 of file VisualServoingServer.h.

◆ l_H_eye_to_r_

yarp::sig::Matrix VisualServoingServer::l_H_eye_to_r_ = yarp::math::zeros(4, 4)
private

Definition at line 216 of file VisualServoingServer.h.

◆ l_H_r_to_cam_

yarp::sig::Matrix VisualServoingServer::l_H_r_to_cam_ = yarp::math::zeros(4, 4)
private

Definition at line 218 of file VisualServoingServer.h.

◆ l_proj_

yarp::sig::Matrix VisualServoingServer::l_proj_
private

Definition at line 211 of file VisualServoingServer.h.

◆ l_px_goal_

std::vector<yarp::sig::Vector> VisualServoingServer::l_px_goal_ = std::vector<yarp::sig::Vector>(4)
private

Definition at line 226 of file VisualServoingServer.h.

◆ max_o_dot_

double VisualServoingServer::max_o_dot_ = 10.0 * M_PI / 180.0
private

Definition at line 196 of file VisualServoingServer.h.

◆ max_x_dot_

double VisualServoingServer::max_x_dot_ = 0.035
private

Definition at line 195 of file VisualServoingServer.h.

◆ mtx_H_eye_cam_

std::mutex VisualServoingServer::mtx_H_eye_cam_
private

Definition at line 222 of file VisualServoingServer.h.

◆ mtx_px_des_

std::mutex VisualServoingServer::mtx_px_des_
private

Definition at line 221 of file VisualServoingServer.h.

◆ op_mode_

OperatingMode VisualServoingServer::op_mode_ = OperatingMode::pose
private

Definition at line 182 of file VisualServoingServer.h.

◆ port_click_left_

yarp::os::BufferedPort<yarp::os::Bottle> VisualServoingServer::port_click_left_
private

Definition at line 237 of file VisualServoingServer.h.

◆ port_click_right_

yarp::os::BufferedPort<yarp::os::Bottle> VisualServoingServer::port_click_right_
private

Definition at line 241 of file VisualServoingServer.h.

◆ port_goal_px_l_

yarp::os::BufferedPort<yarp::sig::Vector> VisualServoingServer::port_goal_px_l_
private

Definition at line 310 of file VisualServoingServer.h.

◆ port_goal_px_r_

yarp::os::BufferedPort<yarp::sig::Vector> VisualServoingServer::port_goal_px_r_
private

Definition at line 311 of file VisualServoingServer.h.

◆ port_image_left_in_

yarp::os::BufferedPort<yarp::sig::ImageOf<yarp::sig::PixelRgb> > VisualServoingServer::port_image_left_in_
private

Definition at line 235 of file VisualServoingServer.h.

◆ port_image_left_out_

yarp::os::BufferedPort<yarp::sig::ImageOf<yarp::sig::PixelRgb> > VisualServoingServer::port_image_left_out_
private

Definition at line 236 of file VisualServoingServer.h.

◆ port_image_right_in_

yarp::os::BufferedPort<yarp::sig::ImageOf<yarp::sig::PixelRgb> > VisualServoingServer::port_image_right_in_
private

Definition at line 239 of file VisualServoingServer.h.

◆ port_image_right_out_

yarp::os::BufferedPort<yarp::sig::ImageOf<yarp::sig::PixelRgb> > VisualServoingServer::port_image_right_out_
private

Definition at line 240 of file VisualServoingServer.h.

◆ port_kin_px_l_

yarp::os::BufferedPort<yarp::sig::Vector> VisualServoingServer::port_kin_px_l_
private

Definition at line 307 of file VisualServoingServer.h.

◆ port_kin_px_r_

yarp::os::BufferedPort<yarp::sig::Vector> VisualServoingServer::port_kin_px_r_
private

Definition at line 308 of file VisualServoingServer.h.

◆ port_pose_avg_

yarp::os::BufferedPort<yarp::sig::Vector> VisualServoingServer::port_pose_avg_
private

Definition at line 313 of file VisualServoingServer.h.

◆ port_pose_goal_

yarp::os::BufferedPort<yarp::sig::Vector> VisualServoingServer::port_pose_goal_
private

Definition at line 315 of file VisualServoingServer.h.

◆ port_pose_kin_

yarp::os::BufferedPort<yarp::sig::Vector> VisualServoingServer::port_pose_kin_
private

Definition at line 314 of file VisualServoingServer.h.

◆ port_pose_left_in_

yarp::os::BufferedPort<yarp::sig::Vector> VisualServoingServer::port_pose_left_in_
private

Definition at line 232 of file VisualServoingServer.h.

◆ port_pose_px_l_

yarp::os::BufferedPort<yarp::sig::Vector> VisualServoingServer::port_pose_px_l_
private

Definition at line 304 of file VisualServoingServer.h.

◆ port_pose_px_r_

yarp::os::BufferedPort<yarp::sig::Vector> VisualServoingServer::port_pose_px_r_
private

Definition at line 305 of file VisualServoingServer.h.

◆ port_pose_right_in_

yarp::os::BufferedPort<yarp::sig::Vector> VisualServoingServer::port_pose_right_in_
private

Definition at line 233 of file VisualServoingServer.h.

◆ port_rpc_command_

yarp::os::Port VisualServoingServer::port_rpc_command_
private

Definition at line 243 of file VisualServoingServer.h.

◆ port_rpc_tracker_left_

yarp::os::RpcClient VisualServoingServer::port_rpc_tracker_left_
private

Definition at line 244 of file VisualServoingServer.h.

◆ port_rpc_tracker_right_

yarp::os::RpcClient VisualServoingServer::port_rpc_tracker_right_
private

Definition at line 245 of file VisualServoingServer.h.

◆ px_des_

yarp::sig::Vector VisualServoingServer::px_des_ = yarp::math::zeros(16)
private

Definition at line 215 of file VisualServoingServer.h.

◆ r_H_eye_to_r_

yarp::sig::Matrix VisualServoingServer::r_H_eye_to_r_ = yarp::math::zeros(4, 4)
private

Definition at line 217 of file VisualServoingServer.h.

◆ r_H_r_to_cam_

yarp::sig::Matrix VisualServoingServer::r_H_r_to_cam_ = yarp::math::zeros(4, 4)
private

Definition at line 219 of file VisualServoingServer.h.

◆ r_proj_

yarp::sig::Matrix VisualServoingServer::r_proj_
private

Definition at line 212 of file VisualServoingServer.h.

◆ r_px_goal_

std::vector<yarp::sig::Vector> VisualServoingServer::r_px_goal_ = std::vector<yarp::sig::Vector>(4)
private

Definition at line 227 of file VisualServoingServer.h.

◆ rightarm_cartesian_driver_

yarp::dev::PolyDriver VisualServoingServer::rightarm_cartesian_driver_
private

Definition at line 184 of file VisualServoingServer.h.

◆ robot_name_

yarp::os::ConstString VisualServoingServer::robot_name_ = "icub"
private

Definition at line 179 of file VisualServoingServer.h.

◆ sim_

bool VisualServoingServer::sim_ = false
private

Definition at line 178 of file VisualServoingServer.h.

◆ thr_background_update_params_

std::thread* VisualServoingServer::thr_background_update_params_
private

Definition at line 224 of file VisualServoingServer.h.

◆ tol_angle_

double VisualServoingServer::tol_angle_ = 1.0 * M_PI / 180.0
private

Definition at line 208 of file VisualServoingServer.h.

◆ tol_orientation_

double VisualServoingServer::tol_orientation_ = 3.0 * M_PI / 180.0
private

Definition at line 207 of file VisualServoingServer.h.

◆ tol_position_

double VisualServoingServer::tol_position_ = 0.01
private

Definition at line 206 of file VisualServoingServer.h.

◆ tol_px_

double VisualServoingServer::tol_px_ = 1.0
private

Definition at line 205 of file VisualServoingServer.h.

◆ traj_time_

double VisualServoingServer::traj_time_ = 1.0
private

Definition at line 209 of file VisualServoingServer.h.

◆ Ts_

const double VisualServoingServer::Ts_ = 0.1
private

Definition at line 192 of file VisualServoingServer.h.

◆ verbosity_

bool VisualServoingServer::verbosity_ = false
private

Definition at line 177 of file VisualServoingServer.h.

◆ vs_control_

VisualServoControl VisualServoingServer::vs_control_ = VisualServoControl::decoupled
private

Definition at line 181 of file VisualServoingServer.h.

◆ vs_control_running_

bool VisualServoingServer::vs_control_running_ = false
private

Definition at line 190 of file VisualServoingServer.h.

◆ vs_goal_reached_

bool VisualServoingServer::vs_goal_reached_ = false
private

Definition at line 191 of file VisualServoingServer.h.


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