#include <shadow_hand.hpp>
Classes | |
class | SrRosWrapper |
Public Member Functions | |
bool | get_control_type (ControlType &control_type) |
std::vector< std::string > | get_controlled_joints () const |
std::map< std::string, JointState > & | get_joint_states () const |
std::vector< std::string > | get_joints_with_state () const |
std::vector< Tactile > & | get_tactiles () const |
void | send_all_positions (const std::vector< double > &targets) |
void | send_all_torques (const std::vector< double > &targets) |
void | send_position (const std::string &joint_name, double target) |
void | send_torque (const std::string &joint_name, double target) |
bool | set_control_type (ControlType control_type) |
ShadowHand () | |
~ShadowHand () | |
Private Member Functions | |
ShadowHand & | operator= (const ShadowHand &other) |
ShadowHand (const ShadowHand &other) | |
Private Attributes | |
SrRosWrapper * | wrapper_ |
Definition at line 40 of file shadow_hand.hpp.
Definition at line 9 of file shadow_hand.cpp.
Definition at line 12 of file shadow_hand.cpp.
shadow_robot_standalone::ShadowHand::ShadowHand | ( | const ShadowHand & | other | ) | [inline, private] |
Definition at line 138 of file shadow_hand.hpp.
bool shadow_robot_standalone::ShadowHand::get_control_type | ( | ControlType & | control_type | ) |
Get the control type currently used on the hand.
control_type | Either position control over PWM, or effort control over Torque. |
Definition at line 17 of file shadow_hand.cpp.
vector< string > shadow_robot_standalone::ShadowHand::get_controlled_joints | ( | ) | const |
Get a list of joint names in the hand that can be controlled
Definition at line 71 of file shadow_hand.cpp.
map< string, JointState > & shadow_robot_standalone::ShadowHand::get_joint_states | ( | ) | const |
Retrieves the latest information about the joints. will be empty if nothing has been published
Definition at line 47 of file shadow_hand.cpp.
vector< string > shadow_robot_standalone::ShadowHand::get_joints_with_state | ( | ) | const |
Get a list of joint names in the hand for which state is reported
Definition at line 59 of file shadow_hand.cpp.
vector< Tactile > & shadow_robot_standalone::ShadowHand::get_tactiles | ( | ) | const |
Retrieves the tactile data from the biotacs.
Definition at line 53 of file shadow_hand.cpp.
ShadowHand& shadow_robot_standalone::ShadowHand::operator= | ( | const ShadowHand & | other | ) | [inline, private] |
Definition at line 140 of file shadow_hand.hpp.
void shadow_robot_standalone::ShadowHand::send_all_positions | ( | const std::vector< double > & | targets | ) |
Send position targets, in radians, to position controllers of all joints. The order in targets is the same as in response from get_controlled_joints()
positions | in radians for all joints |
Definition at line 32 of file shadow_hand.cpp.
void shadow_robot_standalone::ShadowHand::send_all_torques | ( | const std::vector< double > & | targets | ) |
Send torque targets, to all joints. The order in targets is the same as in response from get_controlled_joints()
torque | targets. |
Definition at line 42 of file shadow_hand.cpp.
void shadow_robot_standalone::ShadowHand::send_position | ( | const std::string & | joint_name, |
double | target | ||
) |
Send a position target, in radians, to the given joint's position controller.
joint_name | Name of the joint to control |
a | position in radians |
Definition at line 27 of file shadow_hand.cpp.
void shadow_robot_standalone::ShadowHand::send_torque | ( | const std::string & | joint_name, |
double | target | ||
) |
Send a torque target, to the given joint.
joint_name | Name of the joint to control |
a | torque target. |
Definition at line 37 of file shadow_hand.cpp.
bool shadow_robot_standalone::ShadowHand::set_control_type | ( | ControlType | control_type | ) |
Set the control type to be used on the hand.
control_type | Either position control over PWM, or effort control over Torque. |
Definition at line 22 of file shadow_hand.cpp.
Definition at line 136 of file shadow_hand.hpp.