$search

shadowrobot::RealShadowhand Class Reference

#include <real_shadowhand.h>

Inheritance diagram for shadowrobot::RealShadowhand:
Inheritance graph
[legend]

List of all members.

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 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)
 ~RealShadowhand ()
 Destructor.

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)

Detailed Description

The real shadowhand class is a class used to access the C code of the Dextrous Hand.

Definition at line 54 of file real_shadowhand.h.


Constructor & Destructor Documentation

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 43 of file real_shadowhand.cpp.

shadowrobot::RealShadowhand::~RealShadowhand (  ) 

Destructor.

Definition at line 69 of file real_shadowhand.cpp.


Member Function Documentation

SRArticulatedRobot::JointsMap shadowrobot::RealShadowhand::getAllJointsData (  )  [virtual]

Get the data for all the joints.

Returns:
a mapping between the joints names and the information for each joint.

Implements shadowrobot::SRArticulatedRobot.

Definition at line 211 of file real_shadowhand.cpp.

void shadowrobot::RealShadowhand::getConfig ( std::string  joint_name  )  [virtual]

Get the config of the palm

Todo:
Not implemented yet
Parameters:
joint_name 

Implements shadowrobot::SRArticulatedRobot.

Definition at line 336 of file real_shadowhand.cpp.

JointControllerData shadowrobot::RealShadowhand::getContrl ( std::string  contrlr_name  )  [virtual]

Get the controller parameters for a given controller name.

Parameters:
contrlr_name the name of the controller.
Returns:
The parameters of this controller

Implements shadowrobot::SRArticulatedRobot.

Definition at line 299 of file real_shadowhand.cpp.

std::vector< DiagnosticData > shadowrobot::RealShadowhand::getDiagnostics (  )  [virtual]

Get the diagnostics for the whole articulated robot.

Returns:
A vector containing all the diagnostics for the robot (motor information, etc...)

Implements shadowrobot::SRArticulatedRobot.

Definition at line 341 of file real_shadowhand.cpp.

JointData shadowrobot::RealShadowhand::getJointData ( std::string  joint_name  )  [virtual]

Get the joint data for a specific joint.

See also:
JointData
Parameters:
joint_name The name of the joint, as specified in joints_map.
Returns:
The information regarding this joint.

Implements shadowrobot::SRArticulatedRobot.

Definition at line 166 of file real_shadowhand.cpp.

void shadowrobot::RealShadowhand::initializeMap (  )  [protected]

the parameters for the motors

Definition at line 73 of file real_shadowhand.cpp.

void shadowrobot::RealShadowhand::posttest ( diagnostic_updater::DiagnosticStatusWrapper status  )  [protected]

A set of tasks to run after the tests:

  • release the mutexes
Parameters:
status the status of the posttest

Definition at line 461 of file real_shadowhand.cpp.

void shadowrobot::RealShadowhand::pretest ( diagnostic_updater::DiagnosticStatusWrapper status  )  [protected]

A set of tasks to run before the tests:

  • Ensure we don't use the ROS interface during the tests (lock the mutexes).
Parameters:
status the status of the pretest

Definition at line 445 of file real_shadowhand.cpp.

short shadowrobot::RealShadowhand::sendupdate ( std::string  joint_name,
double  target 
) [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.

Parameters:
joint_name The Joint in joints_map you wish to send the target to.
target The target in degree
Returns:
0 if success ; -1 if error

Implements shadowrobot::SRArticulatedRobot.

Definition at line 136 of file real_shadowhand.cpp.

short shadowrobot::RealShadowhand::setConfig ( std::vector< std::string >  myConfig  )  [virtual]

Set the config of the palm

Todo:
Not implemented yet
Parameters:
myConfig 
Returns:

Implements shadowrobot::SRArticulatedRobot.

Definition at line 317 of file real_shadowhand.cpp.

short shadowrobot::RealShadowhand::setContrl ( std::string  contrlr_name,
JointControllerData  ctrlr_data 
) [virtual]

Set the controller parameters for a given controller name.

Parameters:
contrlr_name The name of the controller to setup.
ctrlr_data The data to pass to this controller.
Returns:
0 if success.

Implements shadowrobot::SRArticulatedRobot.

Definition at line 258 of file real_shadowhand.cpp.

void shadowrobot::RealShadowhand::test_messages ( diagnostic_updater::DiagnosticStatusWrapper status  )  [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.

Parameters:
status the test result.

Definition at line 475 of file real_shadowhand.cpp.

std::pair< unsigned char, std::string > shadowrobot::RealShadowhand::test_messages_routine ( std::string  joint_name,
unsigned int  repeat,
ros::Rate  rate 
) [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.

Parameters:
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
Returns:
a pair containing the status of the test (error or ok), and a message to display.

Definition at line 503 of file real_shadowhand.cpp.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


sr_hand
Author(s): Ugo Cupcic / ugo@shadowrobot.com, contact@shadowrobot.com
autogenerated on Sat Mar 2 14:08:29 2013