Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
generic_control_toolbox Namespace Reference

Namespaces

 manage_actionlib
 

Classes

class  BagManager
 
class  ControllerActionNode
 
class  ControllerBase
 
class  ControllerTemplate
 
class  KDLManager
 
class  ManagerBase
 
class  MarkerManager
 
class  MatrixParser
 
class  RosControlInterface
 
class  WrenchManager
 

Typedefs

typedef boost::shared_ptr< ControllerBaseBasePtr
 

Enumerations

enum  JointType { EFFORT, VELOCITY, POSITION }
 
enum  MarkerType { sphere, arrow }
 

Functions

bool getArmInfo (const std::string &arm_name, ArmInfo &info, ros::NodeHandle &nh)
 
bool getArmInfo (const std::string &arm_name, ArmInfo &info)
 
bool setKDLManager (const ArmInfo &arm_info, std::shared_ptr< KDLManager > manager)
 
bool setKDLManagerNso (const ArmInfo &arm_info, std::shared_ptr< KDLManager > manager)
 
bool setWrenchManager (const ArmInfo &arm_info, WrenchManager &manager)
 
bool setWrenchManager (const ArmInfo &arm_info, std::shared_ptr< WrenchManager > &manager)
 

Variables

const double MAX_DT = 0.5
 

Typedef Documentation

Definition at line 344 of file controller_template.hpp.

Enumeration Type Documentation

Enumerator
EFFORT 
VELOCITY 
POSITION 

Definition at line 11 of file ros_control_interface.hpp.

Enumerator
sphere 
arrow 

Definition at line 13 of file marker_manager.hpp.

Function Documentation

bool generic_control_toolbox::getArmInfo ( const std::string &  arm_name,
ArmInfo &  info,
ros::NodeHandle nh 
)

Fill in an ArmInfo structure with the parameters of the arm. Uses the ros parameter server.

Searches for "arm_name/kdl_eef_frame", "arm_name/gripping_frame", "arm_name/has_state_", "arm_name/sensor_frame" and "arm_name/sensor_topic", relative to the calling node's name.

Parameters
arm_nameThe arm name used in the ros parameter server.
infoThe ArmInfo structure to fill in.
nhThe ros nodehandle
Returns
True for success, false otherwise

Definition at line 15 of file manager_base.cpp.

bool generic_control_toolbox::getArmInfo ( const std::string &  arm_name,
ArmInfo &  info 
)

getArmInfo overload which creates a private nodehandle

Definition at line 8 of file manager_base.cpp.

bool generic_control_toolbox::setKDLManager ( const ArmInfo &  arm_info,
std::shared_ptr< KDLManager manager 
)

Initializes a kdl manager class with the given arm info. Uses the ros parameter server to obtain information.

Parameters
arm_infoThe arm information.
managerReference to the kdl manager.
Returns
False if something goes wrong, true otherwise.

Definition at line 1048 of file kdl_manager.cpp.

bool generic_control_toolbox::setKDLManagerNso ( const ArmInfo &  arm_info,
std::shared_ptr< KDLManager manager 
)

Initializes a kdl manager class with the given arm info. Uses nullspace optimization. Uses the ros parameter server to obtain information.

Parameters
arm_infoThe arm information.
managerReference to the kdl manager.
Returns
False if something goes wrong, true otherwise.
bool generic_control_toolbox::setWrenchManager ( const ArmInfo &  arm_info,
WrenchManager manager 
)

Initializes a wrench manager class with the given arm's sensor info. Uses the ros parameter server to obtain information."

Parameters
arm_infoThe arm information
managerShared pointer to the wrench manager.
Returns
False if something goes wrong, true otherwise.

Definition at line 166 of file wrench_manager.cpp.

bool generic_control_toolbox::setWrenchManager ( const ArmInfo &  arm_info,
std::shared_ptr< WrenchManager > &  manager 
)

Definition at line 190 of file wrench_manager.cpp.

Variable Documentation

const double generic_control_toolbox::MAX_DT = 0.5

Definition at line 13 of file controller_template.hpp.



generic_control_toolbox
Author(s): diogo
autogenerated on Thu Jun 6 2019 19:54:44