visual-tracking-control
|
#include <VisualServoingServer.h>
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 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_ |
Definition at line 32 of file VisualServoingServer.h.
|
strongprotected |
Enumerator | |
---|---|
position | |
orientation | |
pose |
Definition at line 174 of file VisualServoingServer.h.
|
strongprotected |
Enumerator | |
---|---|
all | |
x | |
o |
Definition at line 172 of file VisualServoingServer.h.
|
strongprotected |
Enumerator | |
---|---|
decoupled | |
robust | |
cartesian |
Definition at line 170 of file VisualServoingServer.h.
VisualServoingServer::VisualServoingServer | ( | ) |
Definition at line 20 of file VisualServoingServer.cpp.
VisualServoingServer::~VisualServoingServer | ( | ) |
Definition at line 27 of file VisualServoingServer.cpp.
|
overrideprotected |
Definition at line 1032 of file VisualServoingServer.cpp.
|
private |
Definition at line 2818 of file VisualServoingServer.cpp.
References checkVisualServoingStatus().
|
private |
Definition at line 2796 of file VisualServoingServer.cpp.
Referenced by threadInit().
|
overrideprotected |
Definition at line 986 of file VisualServoingServer.cpp.
|
private |
Definition at line 2071 of file VisualServoingServer.cpp.
|
overrideprotectedvirtual |
Check once whether the visual servoing controller is running or not.
Reimplemented from VisualServoingIDL.
Definition at line 1220 of file VisualServoingServer.cpp.
|
override |
Definition at line 589 of file VisualServoingServer.cpp.
|
private |
Referenced by averagePose().
|
private |
|
override |
Definition at line 185 of file VisualServoingServer.cpp.
|
private |
Definition at line 1315 of file VisualServoingServer.cpp.
|
override |
Definition at line 675 of file VisualServoingServer.cpp.
|
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.
x | a 3D vector which is filled with the actual position (x, y, z) [m]. |
o | a 4D vector which is filled with the actual orientation using axis-angle representation (xa, ya, za) and (theta) [rad]. |
Reimplemented from VisualServoingIDL.
Definition at line 1274 of file VisualServoingServer.cpp.
|
overrideprotectedvirtual |
Get goal point from SFM module.
The point is taken by clicking on a dedicated 'yarpview' GUI and the orientation is hard-coded.
Reimplemented from VisualServoingIDL.
Definition at line 1099 of file VisualServoingServer.cpp.
|
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.
x | a 3D vector which is filled with the actual position (x, y, z) [m]. |
o | a 4D vector which is filled with the actual orientation using axis-angle representation (xa, ya, za) and (theta) [m]/[rad]. |
cam | either "left" or "right" to select left or right camera. |
Reimplemented from VisualServoingIDL.
Definition at line 1292 of file VisualServoingServer.cpp.
|
overrideprotectedvirtual |
Return useful information for visual servoing.
Reimplemented from VisualServoingIDL.
Definition at line 1202 of file VisualServoingServer.cpp.
|
private |
Definition at line 2626 of file VisualServoingServer.cpp.
|
private |
Definition at line 2553 of file VisualServoingServer.cpp.
|
private |
Definition at line 2576 of file VisualServoingServer.cpp.
|
private |
Definition at line 2646 of file VisualServoingServer.cpp.
|
override |
Definition at line 695 of file VisualServoingServer.cpp.
|
private |
Definition at line 2685 of file VisualServoingServer.cpp.
|
private |
Definition at line 2710 of file VisualServoingServer.cpp.
|
private |
Definition at line 2620 of file VisualServoingServer.cpp.
|
private |
Definition at line 2537 of file VisualServoingServer.cpp.
|
override |
Definition at line 573 of file VisualServoingServer.cpp.
|
overrideprotectedvirtual |
Set the goal point (3D for the position + 4D axis-angle for the orientation) and start visual servoing.
vec_x | a 3D vector which contains the (x, y, z) Cartesian coordinates of the goal. |
vec_o | a 4D vector which contains the (x, y, z) axis and theta angle of rotation of the goal. |
Reimplemented from VisualServoingIDL.
Definition at line 1172 of file VisualServoingServer.cpp.
|
virtualinherited |
Set the goal points on both left and right camera image plane and start visual servoing.
vec_px_l | a collection of four 2D vectors which contains the (u, v) coordinates of the pixels within the left image plane. |
vec_px_r | a collection of four 2D vectors which contains the (u, v) coordinates of the pixels within the right image plane. |
|
overrideprotected |
Definition at line 1145 of file VisualServoingServer.cpp.
|
override |
Referenced by stopFacilities().
|
override |
|
override |
Definition at line 925 of file VisualServoingServer.cpp.
|
virtualinherited |
|
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.
use_direct_kin | instruct the visual servoing control to either use direct kinematic or an estimated/refined pose of the end-effector. |
Reimplemented from VisualServoingIDL.
Definition at line 1127 of file VisualServoingServer.cpp.
|
override |
Definition at line 253 of file VisualServoingServer.cpp.
|
overrideprotected |
Definition at line 1051 of file VisualServoingServer.cpp.
|
override |
Definition at line 35 of file VisualServoingServer.cpp.
|
overrideprotectedvirtual |
Gently close the visual servoing device, deallocating resources.
Reimplemented from VisualServoingIDL.
Definition at line 1105 of file VisualServoingServer.cpp.
|
overridevirtualinherited |
|
overrideprotectedvirtual |
Reset support modules and connections to perform the current initialized visual servoing task.
Returns upon successful or failure setup.
Reimplemented from VisualServoingIDL.
Definition at line 1133 of file VisualServoingServer.cpp.
|
override |
Definition at line 367 of file VisualServoingServer.cpp.
|
private |
Definition at line 1716 of file VisualServoingServer.cpp.
|
overrideprotected |
Definition at line 1021 of file VisualServoingServer.cpp.
|
overrideprotectedvirtual |
Set the point controlled during visual servoing.
point | label of the point to control. |
Reimplemented from VisualServoingIDL.
Definition at line 1196 of file VisualServoingServer.cpp.
|
overrideprotectedvirtual |
Set visual servoing goal tolerance.
tol | the tolerance in pixel. |
Reimplemented from VisualServoingIDL.
Definition at line 1214 of file VisualServoingServer.cpp.
|
overrideprotectedvirtual |
Set the maximum angular velocity of the axis-angle velocity vector of the visual servoing control algorithm.
max_x_dot | the maximum allowed angular velocity [rad/s]. |
Reimplemented from VisualServoingIDL.
Definition at line 1262 of file VisualServoingServer.cpp.
|
overrideprotectedvirtual |
Set the maximum translation velocity of the visual servoing control algorithm (same for each axis).
max_x_dot | the maximum allowed velocity for x, y, z coordinates [m/s]. |
Reimplemented from VisualServoingIDL.
Definition at line 1244 of file VisualServoingServer.cpp.
|
overrideprotectedvirtual |
Set visual servoing operating mode between:
mode | a label referring to one of the three operating mode, i.e. 'position', 'orientation' or 'pose'. |
Reimplemented from VisualServoingIDL.
Definition at line 1184 of file VisualServoingServer.cpp.
|
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.
Reimplemented from VisualServoingIDL.
Definition at line 1256 of file VisualServoingServer.cpp.
|
overrideprotectedvirtual |
Set the tolerance, in pixels, at which the orientation control law swithces its gain value.
Reimplemented from VisualServoingIDL.
Definition at line 1268 of file VisualServoingServer.cpp.
|
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.
Reimplemented from VisualServoingIDL.
Definition at line 1238 of file VisualServoingServer.cpp.
|
overrideprotectedvirtual |
Set the tolerance, in pixels, at which the translation control law swithces its gain value.
Reimplemented from VisualServoingIDL.
Definition at line 1250 of file VisualServoingServer.cpp.
|
overrideprotectedvirtual |
Set visual servo control law between:
mode | a label referring to one of the three visual servo controls, i.e. 'position', 'orientation' or 'pose'. |
Reimplemented from VisualServoingIDL.
Definition at line 1190 of file VisualServoingServer.cpp.
|
private |
Definition at line 2735 of file VisualServoingServer.cpp.
|
private |
Definition at line 2457 of file VisualServoingServer.cpp.
|
override |
Definition at line 565 of file VisualServoingServer.cpp.
|
private |
Definition at line 2430 of file VisualServoingServer.cpp.
|
override |
Definition at line 581 of file VisualServoingServer.cpp.
|
override |
Definition at line 659 of file VisualServoingServer.cpp.
|
override |
Definition at line 634 of file VisualServoingServer.cpp.
|
override |
Definition at line 535 of file VisualServoingServer.cpp.
|
override |
Definition at line 650 of file VisualServoingServer.cpp.
|
override |
Definition at line 667 of file VisualServoingServer.cpp.
|
private |
Definition at line 2776 of file VisualServoingServer.cpp.
|
private |
Definition at line 2767 of file VisualServoingServer.cpp.
|
private |
Definition at line 2353 of file VisualServoingServer.cpp.
|
private |
Definition at line 2491 of file VisualServoingServer.cpp.
|
override |
Definition at line 625 of file VisualServoingServer.cpp.
|
override |
Definition at line 642 of file VisualServoingServer.cpp.
|
override |
Definition at line 550 of file VisualServoingServer.cpp.
|
private |
Definition at line 2863 of file VisualServoingServer.cpp.
Referenced by yErrorVerbose().
|
overrideprotectedvirtual |
Ask for an immediate stop of the visual servoing controller.
[wait for reply]
Reimplemented from VisualServoingIDL.
Definition at line 1232 of file VisualServoingServer.cpp.
|
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.
Reimplemented from VisualServoingIDL.
Definition at line 1139 of file VisualServoingServer.cpp.
|
override |
Definition at line 613 of file VisualServoingServer.cpp.
|
override |
Definition at line 402 of file VisualServoingServer.cpp.
References goToGoal().
|
overrideprotectedvirtual |
Set the robot visual servoing goal.
The goals are stored on an external file and are referenced by a unique label.
label | a label referring to one of the available goals; the string shall be one of the available modes returned by the get_info() method. |
Reimplemented from VisualServoingIDL.
Definition at line 1093 of file VisualServoingServer.cpp.
|
overrideprotectedvirtual |
Initialize the robot to an initial position.
The initial positions are stored on an external file and are referenced by a unique label.
label | a label referring to one of the available initial positions; the string shall be one of the available modes returned by the get_info() method. |
Reimplemented from VisualServoingIDL.
Definition at line 1087 of file VisualServoingServer.cpp.
|
override |
Definition at line 846 of file VisualServoingServer.cpp.
|
override |
Definition at line 718 of file VisualServoingServer.cpp.
|
overrideprotected |
Definition at line 992 of file VisualServoingServer.cpp.
References backproc_UpdateVisualServoingParamters().
|
overrideprotected |
Definition at line 1057 of file VisualServoingServer.cpp.
|
private |
Definition at line 2514 of file VisualServoingServer.cpp.
|
overrideprotectedvirtual |
Wait until visual servoing reaches the goal.
[wait for reply]
period | the check time period [s]. |
timeout | the check expiration time [s]. If timeout <= 0 (as by default) the check will be performed without time limitation. |
Reimplemented from VisualServoingIDL.
Definition at line 1226 of file VisualServoingServer.cpp.
|
override |
Definition at line 601 of file VisualServoingServer.cpp.
|
inlineprivate |
Definition at line 300 of file VisualServoingServer.h.
References stdVectorOfVectorsToVector().
|
inlineprivate |
Definition at line 298 of file VisualServoingServer.h.
|
inlineprivate |
Definition at line 299 of file VisualServoingServer.h.
|
private |
Definition at line 229 of file VisualServoingServer.h.
|
private |
Definition at line 230 of file VisualServoingServer.h.
|
private |
Definition at line 187 of file VisualServoingServer.h.
|
private |
Definition at line 214 of file VisualServoingServer.h.
|
private |
Definition at line 288 of file VisualServoingServer.h.
|
private |
Definition at line 188 of file VisualServoingServer.h.
|
private |
Definition at line 185 of file VisualServoingServer.h.
|
private |
Definition at line 201 of file VisualServoingServer.h.
|
private |
Definition at line 194 of file VisualServoingServer.h.
|
private |
Definition at line 203 of file VisualServoingServer.h.
|
private |
Definition at line 198 of file VisualServoingServer.h.
|
private |
Definition at line 200 of file VisualServoingServer.h.
|
private |
Definition at line 204 of file VisualServoingServer.h.
|
private |
Definition at line 199 of file VisualServoingServer.h.
|
private |
Definition at line 193 of file VisualServoingServer.h.
|
private |
Definition at line 202 of file VisualServoingServer.h.
|
private |
Definition at line 197 of file VisualServoingServer.h.
|
private |
Definition at line 216 of file VisualServoingServer.h.
|
private |
Definition at line 218 of file VisualServoingServer.h.
|
private |
Definition at line 211 of file VisualServoingServer.h.
|
private |
Definition at line 226 of file VisualServoingServer.h.
|
private |
Definition at line 196 of file VisualServoingServer.h.
|
private |
Definition at line 195 of file VisualServoingServer.h.
|
private |
Definition at line 222 of file VisualServoingServer.h.
|
private |
Definition at line 221 of file VisualServoingServer.h.
|
private |
Definition at line 182 of file VisualServoingServer.h.
|
private |
Definition at line 237 of file VisualServoingServer.h.
|
private |
Definition at line 241 of file VisualServoingServer.h.
|
private |
Definition at line 310 of file VisualServoingServer.h.
|
private |
Definition at line 311 of file VisualServoingServer.h.
|
private |
Definition at line 235 of file VisualServoingServer.h.
|
private |
Definition at line 236 of file VisualServoingServer.h.
|
private |
Definition at line 239 of file VisualServoingServer.h.
|
private |
Definition at line 240 of file VisualServoingServer.h.
|
private |
Definition at line 307 of file VisualServoingServer.h.
|
private |
Definition at line 308 of file VisualServoingServer.h.
|
private |
Definition at line 313 of file VisualServoingServer.h.
|
private |
Definition at line 315 of file VisualServoingServer.h.
|
private |
Definition at line 314 of file VisualServoingServer.h.
|
private |
Definition at line 232 of file VisualServoingServer.h.
|
private |
Definition at line 304 of file VisualServoingServer.h.
|
private |
Definition at line 305 of file VisualServoingServer.h.
|
private |
Definition at line 233 of file VisualServoingServer.h.
|
private |
Definition at line 243 of file VisualServoingServer.h.
|
private |
Definition at line 244 of file VisualServoingServer.h.
|
private |
Definition at line 245 of file VisualServoingServer.h.
|
private |
Definition at line 215 of file VisualServoingServer.h.
|
private |
Definition at line 217 of file VisualServoingServer.h.
|
private |
Definition at line 219 of file VisualServoingServer.h.
|
private |
Definition at line 212 of file VisualServoingServer.h.
|
private |
Definition at line 227 of file VisualServoingServer.h.
|
private |
Definition at line 184 of file VisualServoingServer.h.
|
private |
Definition at line 179 of file VisualServoingServer.h.
|
private |
Definition at line 178 of file VisualServoingServer.h.
|
private |
Definition at line 224 of file VisualServoingServer.h.
|
private |
Definition at line 208 of file VisualServoingServer.h.
|
private |
Definition at line 207 of file VisualServoingServer.h.
|
private |
Definition at line 206 of file VisualServoingServer.h.
|
private |
Definition at line 205 of file VisualServoingServer.h.
|
private |
Definition at line 209 of file VisualServoingServer.h.
|
private |
Definition at line 192 of file VisualServoingServer.h.
|
private |
Definition at line 177 of file VisualServoingServer.h.
|
private |
Definition at line 181 of file VisualServoingServer.h.
|
private |
Definition at line 190 of file VisualServoingServer.h.
|
private |
Definition at line 191 of file VisualServoingServer.h.