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 int16_t | sendupdate (std::string joint_name, double target) |
virtual int16_t | setConfig (std::vector< std::string > myConfig) |
virtual int16_t | setContrl (std::string contrlr_name, JointControllerData ctrlr_data) |
VirtualShadowhand () | |
virtual | ~VirtualShadowhand () |
Public Member Functions inherited from shadowrobot::SRArticulatedRobot | |
SRArticulatedRobot () | |
virtual | ~SRArticulatedRobot () |
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. More... | |
ros::NodeHandle | n_tilde |
ros::NodeHandle | node |
ROS Node handles. More... | |
Protected Attributes inherited from shadowrobot::SRArticulatedRobot | |
boost::shared_ptr< self_test::TestRunner > | self_test |
this is the handle for the self tests. More... | |
Additional Inherited Members | |
Public Types inherited from shadowrobot::SRArticulatedRobot | |
typedef std::map< std::string, JointData > | JointsMap |
typedef std::map< std::string, enum controller_parameters > | ParametersMap |
Public Attributes inherited from shadowrobot::SRArticulatedRobot | |
boost::mutex | controllers_map_mutex |
JointsMap | joints_map |
A mapping between the joint names and the information regarding those joints. More... | |
boost::mutex | joints_map_mutex |
ParametersMap | parameters_map |
A mapping between the parameter names and their values. More... | |
boost::mutex | parameters_map_mutex |
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 46 of file virtual_shadowhand.h.
|
protected |
Definition at line 117 of file virtual_shadowhand.h.
shadowrobot::VirtualShadowhand::VirtualShadowhand | ( | ) |
Initializes the necessary mappings with a static list of names.
Definition at line 46 of file virtual_shadowhand.cpp.
|
virtual |
Definition at line 67 of file virtual_shadowhand.cpp.
|
virtual |
Get the data for all the joints.
Implements shadowrobot::SRArticulatedRobot.
Definition at line 352 of file virtual_shadowhand.cpp.
|
virtual |
Get the config of the palm
joint_name |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 420 of file virtual_shadowhand.cpp.
|
virtual |
Get the controller parameters for a given controller name.
contrlr_name | the name of the controller. |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 395 of file virtual_shadowhand.cpp.
|
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 425 of file virtual_shadowhand.cpp.
|
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 324 of file virtual_shadowhand.cpp.
|
protected |
Initialize a mapping for the joints as well as a mapping for the controllers.
Definition at line 71 of file virtual_shadowhand.cpp.
|
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 225 of file virtual_shadowhand.cpp.
|
virtual |
Set the config of the palm
myConfig |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 414 of file virtual_shadowhand.cpp.
|
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 375 of file virtual_shadowhand.cpp.
|
inlineprotected |
Convert an angle in radian to an angle in degrees.
rad | the angle in rads |
Definition at line 136 of file virtual_shadowhand.h.
|
inlineprotected |
Convert an angle in degree to an angle in radians.
deg | the angle in degrees |
Definition at line 126 of file virtual_shadowhand.h.
|
protected |
Contains the mapping between the controller names and their data.
Definition at line 119 of file virtual_shadowhand.h.
|
protected |
Definition at line 99 of file virtual_shadowhand.h.
|
protected |
ROS Node handles.
Definition at line 99 of file virtual_shadowhand.h.