#include <real_shadowhand.h>
Public Member Functions | |
virtual JointsMap | getAllJointsData () |
virtual void | getConfig (std::string joint_name) |
virtual JointControllerData | getContrl (std::string contrlr_name) |
virtual std::vector< DiagnosticData > | getDiagnostics () |
virtual JointData | getJointData (std::string joint_name) |
RealShadowhand () | |
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) |
virtual | ~RealShadowhand () |
Public Member Functions inherited from shadowrobot::SRArticulatedRobot | |
SRArticulatedRobot () | |
virtual | ~SRArticulatedRobot () |
Protected Member Functions | |
void | initializeMap () |
void | posttest (diagnostic_updater::DiagnosticStatusWrapper &status) |
void | pretest (diagnostic_updater::DiagnosticStatusWrapper &status) |
void | test_messages (diagnostic_updater::DiagnosticStatusWrapper &status) |
std::pair< unsigned char, std::string > | test_messages_routine (std::string joint_name, unsigned int repeat, ros::Rate rate) |
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 |
Protected Attributes inherited from shadowrobot::SRArticulatedRobot | |
boost::shared_ptr< self_test::TestRunner > | self_test |
this is the handle for the self tests. More... | |
The real shadowhand class is a class used to access the C code of the Dextrous Hand.
Definition at line 57 of file real_shadowhand.h.
shadowrobot::RealShadowhand::RealShadowhand | ( | ) |
Constructor for the real Shadowhand: initialize the connection to the robot and also initialize the joint_map containing the mapping between joint_names and their data.
Definition at line 48 of file real_shadowhand.cpp.
|
virtual |
Definition at line 74 of file real_shadowhand.cpp.
|
virtual |
Get the data for all the joints.
Implements shadowrobot::SRArticulatedRobot.
Definition at line 220 of file real_shadowhand.cpp.
|
virtual |
Get the config of the palm
joint_name |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 346 of file real_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 310 of file real_shadowhand.cpp.
|
virtual |
Get the diagnostics for the whole articulated robot.
Implements shadowrobot::SRArticulatedRobot.
Definition at line 351 of file real_shadowhand.cpp.
|
virtual |
Get the joint data for a specific joint.
joint_name | The name of the joint, as specified in joints_map. |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 175 of file real_shadowhand.cpp.
|
protected |
Definition at line 78 of file real_shadowhand.cpp.
|
protected |
A set of tasks to run after the tests:
status | the status of the posttest |
Definition at line 471 of file real_shadowhand.cpp.
|
protected |
A set of tasks to run before the tests:
status | the status of the pretest |
Definition at line 455 of file real_shadowhand.cpp.
|
virtual |
Send a new target to a given joint on the robot. The command will be issued to the robot which will move if the controllers are started and tuned. The target is truncated to the correct range.
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 141 of file real_shadowhand.cpp.
|
virtual |
Set the config of the palm
myConfig |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 327 of file real_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 269 of file real_shadowhand.cpp.
|
protected |
A test to check the number of messages received is the same as the number of messages sent. Calls the test_messages_routine for each joint / frequency we're testing.
status | the test result. |
Definition at line 485 of file real_shadowhand.cpp.
|
protected |
The routine called during the test: test the number of received messages for a given joint, a given number of times and at a given frequency.
joint_name | the name of the joint to test |
repeat | the number of messages to send |
rate | the rate at which we send the messages |
Definition at line 516 of file real_shadowhand.cpp.