$search
The Virtual Shadowhand can be used as a simulator. As both the real hand and the virtual hand are children from the shadowhand class, using a virtual or a real hand doesn't change anything in the way you call them in your programs. More...
#include <virtual_shadowhand.h>
Public Member Functions | |
virtual JointsMap | getAllJointsData () |
virtual void | getConfig (std::string joint_name) |
virtual JointControllerData | getContrl (std::string ctrlr_name) |
virtual std::vector < DiagnosticData > | getDiagnostics () |
virtual JointData | getJointData (std::string joint_name) |
virtual short | sendupdate (std::string joint_name, double target) |
virtual short | setConfig (std::vector< std::string > myConfig) |
virtual short | setContrl (std::string contrlr_name, JointControllerData ctrlr_data) |
VirtualShadowhand () | |
~VirtualShadowhand () | |
destructor | |
Protected Types | |
typedef std::map< std::string, JointControllerData > | ControllersMap |
Protected Member Functions | |
void | initializeMap () |
double | toDegrees (double rad) |
double | toRad (double deg) |
Protected Attributes | |
ControllersMap | controllers_map |
Contains the mapping between the controller names and their data. | |
ros::NodeHandle | n_tilde |
ros::NodeHandle | node |
ROS Node handles. |
The Virtual Shadowhand can be used as a simulator. As both the real hand and the virtual hand are children from the shadowhand class, using a virtual or a real hand doesn't change anything in the way you call them in your programs.
Definition at line 43 of file virtual_shadowhand.h.
typedef std::map<std::string, JointControllerData> shadowrobot::VirtualShadowhand::ControllersMap [protected] |
Definition at line 109 of file virtual_shadowhand.h.
shadowrobot::VirtualShadowhand::VirtualShadowhand | ( | ) |
Initializes the necessary mappings with a static list of names.
Definition at line 43 of file virtual_shadowhand.cpp.
shadowrobot::VirtualShadowhand::~VirtualShadowhand | ( | ) |
destructor
Definition at line 64 of file virtual_shadowhand.cpp.
SRArticulatedRobot::JointsMap shadowrobot::VirtualShadowhand::getAllJointsData | ( | ) | [virtual] |
Get the data for all the joints.
Implements shadowrobot::SRArticulatedRobot.
Definition at line 340 of file virtual_shadowhand.cpp.
void shadowrobot::VirtualShadowhand::getConfig | ( | std::string | joint_name | ) | [virtual] |
Get the config of the palm
joint_name |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 408 of file virtual_shadowhand.cpp.
JointControllerData shadowrobot::VirtualShadowhand::getContrl | ( | std::string | contrlr_name | ) | [virtual] |
Get the controller parameters for a given controller name.
contrlr_name | the name of the controller. |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 383 of file virtual_shadowhand.cpp.
std::vector< DiagnosticData > shadowrobot::VirtualShadowhand::getDiagnostics | ( | ) | [virtual] |
Generates a set of random data to be published by the diagnostic publisher, but keep the position and target as they are ( those are updated by the sendupdate() function).
Implements shadowrobot::SRArticulatedRobot.
Definition at line 413 of file virtual_shadowhand.cpp.
JointData shadowrobot::VirtualShadowhand::getJointData | ( | std::string | joint_name | ) | [virtual] |
In the virtual hand, getJointData() simply fetches the data from a given joint in the joints_map. As the targets and positions are up to date, there's no need of reading other values here for those two values. However, we generate random values for the other data (temperature, current, etc...)
joint_name | The name of the joint, as specified in joints_map. |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 312 of file virtual_shadowhand.cpp.
void shadowrobot::VirtualShadowhand::initializeMap | ( | ) | [protected] |
Initialize a mapping for the joints as well as a mapping for the controllers.
the parameters for the motors
Definition at line 68 of file virtual_shadowhand.cpp.
short shadowrobot::VirtualShadowhand::sendupdate | ( | std::string | joint_name, | |
double | target | |||
) | [virtual] |
This function will set the target of the object to the given angle. It will also set the position to this target.
joint_name | The Joint in joints_map you wish to send the target to. | |
target | The target in degree |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 221 of file virtual_shadowhand.cpp.
short shadowrobot::VirtualShadowhand::setConfig | ( | std::vector< std::string > | myConfig | ) | [virtual] |
Set the config of the palm
myConfig |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 402 of file virtual_shadowhand.cpp.
short shadowrobot::VirtualShadowhand::setContrl | ( | std::string | contrlr_name, | |
JointControllerData | ctrlr_data | |||
) | [virtual] |
Set the controller parameters for a given controller name.
contrlr_name | The name of the controller to setup. | |
ctrlr_data | The data to pass to this controller. |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 363 of file virtual_shadowhand.cpp.
double shadowrobot::VirtualShadowhand::toDegrees | ( | double | rad | ) | [inline, protected] |
Convert an angle in radian to an angle in degrees.
deg | the angle in rads |
Definition at line 128 of file virtual_shadowhand.h.
double shadowrobot::VirtualShadowhand::toRad | ( | double | deg | ) | [inline, protected] |
Convert an angle in degree to an angle in radians.
deg | the angle in degrees |
Definition at line 118 of file virtual_shadowhand.h.
Contains the mapping between the controller names and their data.
Definition at line 111 of file virtual_shadowhand.h.
Definition at line 91 of file virtual_shadowhand.h.
ros::NodeHandle shadowrobot::VirtualShadowhand::node [protected] |
ROS Node handles.
Definition at line 91 of file virtual_shadowhand.h.