ROS-UVS  1.0.0
A Minimalistic ROS Library for Visual Constraint Minimization through Uncalibrated Visual Servoing
 All Classes Files Functions Variables
WamController Class Reference

#include <wam_controller.h>

Inheritance diagram for WamController:
Collaboration diagram for WamController:

Public Member Functions

 WamController (std::string robot_ns, ros::NodeHandle nh)
 
bool initialize ()
 
bool close_grasp ()
 
bool open_grasp ()
 
bool open_spread ()
 
bool close_spread ()
 
bool grasp_pos (double radians)
 
bool spread_pos (double radians)
 
bool pinch_pos (double radians)
 
bool finger_pos (double f1, double f2, double f3)
 
bool reset ()
 
bool set_2_finger_grasp ()
 
bool set_3_finger_grasp ()
 
bool delta_move (const Eigen::VectorXd &delta)
 
bool rt_delta_move (const Eigen::VectorXd &delta)
 
bool joint_move (const Eigen::VectorXd &target_jnt_state)
 
bool move_to_initial_position ()
 
bool play_motion (std::string motion)
 
bool hold_joints (bool hold_joints)
 
geometry_msgs::PoseStamped get_pose ()
 
Eigen::VectorXd get_jnt_state ()
 
Eigen::VectorXd get_used_jnt_state ()
 
size_t get_dof ()
 
std::vector< int > get_used_joints ()
 
void set_used_joints (std::string)
 
void set_used_joints (std::vector< int > new_joints)
 
void set_target_joint_pose (Eigen::VectorXd target)
 
Eigen::VectorXd map_joints (const Eigen::VectorXd &delta)
 

Public Attributes

double max_rate = 0.01
 

Constructor & Destructor Documentation

WamController::WamController ( std::string  robot_ns,
ros::NodeHandle  nh 
)

Member Function Documentation

bool WamController::close_grasp ( )
bool WamController::close_spread ( )

Here is the caller graph for this function:

bool WamController::delta_move ( const Eigen::VectorXd &  delta)
virtual

Implements RobotController.

Here is the call graph for this function:

bool WamController::finger_pos ( double  f1,
double  f2,
double  f3 
)
size_t WamController::get_dof ( )
inlinevirtual

Reimplemented from RobotController.

Here is the caller graph for this function:

Eigen::VectorXd WamController::get_jnt_state ( )
virtual

Implements RobotController.

Here is the call graph for this function:

Here is the caller graph for this function:

geometry_msgs::PoseStamped WamController::get_pose ( )
inline
Eigen::VectorXd WamController::get_used_jnt_state ( )
virtual

Implements RobotController.

std::vector<int> WamController::get_used_joints ( )
inlinevirtual

Implements RobotController.

Here is the caller graph for this function:

bool WamController::grasp_pos ( double  radians)

Here is the caller graph for this function:

bool WamController::hold_joints ( bool  hold_joints)

Here is the caller graph for this function:

bool WamController::initialize ( )
bool WamController::joint_move ( const Eigen::VectorXd &  target_jnt_state)

Here is the caller graph for this function:

Eigen::VectorXd WamController::map_joints ( const Eigen::VectorXd &  delta)
virtual

Implements RobotController.

Here is the call graph for this function:

Here is the caller graph for this function:

bool WamController::move_to_initial_position ( )

Here is the call graph for this function:

bool WamController::open_grasp ( )

Here is the caller graph for this function:

bool WamController::open_spread ( )

Here is the caller graph for this function:

bool WamController::pinch_pos ( double  radians)
bool WamController::play_motion ( std::string  motion)
bool WamController::reset ( )

Here is the call graph for this function:

bool WamController::rt_delta_move ( const Eigen::VectorXd &  delta)
virtual

Implements RobotController.

Here is the call graph for this function:

bool WamController::set_2_finger_grasp ( )

Here is the call graph for this function:

bool WamController::set_3_finger_grasp ( )

Here is the call graph for this function:

void WamController::set_target_joint_pose ( Eigen::VectorXd  target)
virtual

Implements RobotController.

void WamController::set_used_joints ( std::string  new_joints)
virtual

Implements RobotController.

void WamController::set_used_joints ( std::vector< int >  new_joints)
virtual

Implements RobotController.

bool WamController::spread_pos ( double  radians)

Here is the caller graph for this function:

Member Data Documentation

double WamController::max_rate = 0.01

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